opengv/0000775016516101651610000000000014257363042011010 5ustar dimadimaopengv/modules/0000775016516101651610000000000013635643413012462 5ustar dimadimaopengv/modules/FindNumPy.cmake0000664016516101651610000001016713635643413015342 0ustar dimadima# - Find the NumPy libraries # This module finds if NumPy is installed, and sets the following variables # indicating where it is. # # TODO: Update to provide the libraries and paths for linking npymath lib. # # NUMPY_FOUND - was NumPy found # NUMPY_VERSION - the version of NumPy found as a string # NUMPY_VERSION_MAJOR - the major version number of NumPy # NUMPY_VERSION_MINOR - the minor version number of NumPy # NUMPY_VERSION_PATCH - the patch version number of NumPy # NUMPY_VERSION_DECIMAL - e.g. version 1.6.1 is 10601 # NUMPY_INCLUDE_DIRS - path to the NumPy include files #============================================================================ # Copyright 2012 Continuum Analytics, Inc. # # MIT License # # Permission is hereby granted, free of charge, to any person obtaining # a copy of this software and associated documentation files # (the "Software"), to deal in the Software without restriction, including # without limitation the rights to use, copy, modify, merge, publish, # distribute, sublicense, and/or sell copies of the Software, and to permit # persons to whom the Software is furnished to do so, subject to # the following conditions: # # The above copyright notice and this permission notice shall be included # in all copies or substantial portions of the Software. # # THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS # OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, # FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL # THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR # OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, # ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR # OTHER DEALINGS IN THE SOFTWARE. # #============================================================================ # Finding NumPy involves calling the Python interpreter if(NumPy_FIND_REQUIRED) find_package(PythonInterp REQUIRED) else() find_package(PythonInterp) endif() if(NOT PYTHONINTERP_FOUND) set(NUMPY_FOUND FALSE) return() endif() if($ENV{TRAVIS}) set(PYTHON_EXECUTABLE "/usr/bin/python") endif() execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" "import numpy as n; print(n.__version__); print(n.get_include());" RESULT_VARIABLE _NUMPY_SEARCH_SUCCESS OUTPUT_VARIABLE _NUMPY_VALUES_OUTPUT ERROR_VARIABLE _NUMPY_ERROR_VALUE OUTPUT_STRIP_TRAILING_WHITESPACE) if(NOT _NUMPY_SEARCH_SUCCESS MATCHES 0) if(NumPy_FIND_REQUIRED) message(FATAL_ERROR "NumPy import failure:\n${_NUMPY_ERROR_VALUE}") endif() set(NUMPY_FOUND FALSE) return() endif() # Convert the process output into a list string(REGEX REPLACE ";" "\\\\;" _NUMPY_VALUES ${_NUMPY_VALUES_OUTPUT}) string(REGEX REPLACE "\n" ";" _NUMPY_VALUES ${_NUMPY_VALUES}) # Just in case there is unexpected output from the Python command. list(GET _NUMPY_VALUES -2 NUMPY_VERSION) list(GET _NUMPY_VALUES -1 NUMPY_INCLUDE_DIRS) string(REGEX MATCH "^[0-9]+\\.[0-9]+\\.[0-9]+" _VER_CHECK "${NUMPY_VERSION}") if("${_VER_CHECK}" STREQUAL "") # The output from Python was unexpected. Raise an error always # here, because we found NumPy, but it appears to be corrupted somehow. message(FATAL_ERROR "Requested version and include path from NumPy, got instead:\n${_NUMPY_VALUES_OUTPUT}\n") return() endif() # Make sure all directory separators are '/' string(REGEX REPLACE "\\\\" "/" NUMPY_INCLUDE_DIRS ${NUMPY_INCLUDE_DIRS}) # Get the major and minor version numbers string(REGEX REPLACE "\\." ";" _NUMPY_VERSION_LIST ${NUMPY_VERSION}) list(GET _NUMPY_VERSION_LIST 0 NUMPY_VERSION_MAJOR) list(GET _NUMPY_VERSION_LIST 1 NUMPY_VERSION_MINOR) list(GET _NUMPY_VERSION_LIST 2 NUMPY_VERSION_PATCH) string(REGEX MATCH "[0-9]*" NUMPY_VERSION_PATCH ${NUMPY_VERSION_PATCH}) math(EXPR NUMPY_VERSION_DECIMAL "(${NUMPY_VERSION_MAJOR} * 10000) + (${NUMPY_VERSION_MINOR} * 100) + ${NUMPY_VERSION_PATCH}") find_package_message(NUMPY "Found NumPy: version \"${NUMPY_VERSION}\" ${NUMPY_INCLUDE_DIRS}" "${NUMPY_INCLUDE_DIRS}${NUMPY_VERSION}") set(NUMPY_FOUND TRUE) opengv/modules/Config.cmake.in0000664016516101651610000000017513635643413015301 0ustar dimadima@PACKAGE_INIT@ include("${CMAKE_CURRENT_LIST_DIR}/@targets_export_name@.cmake") check_required_components("@PROJECT_NAME@") opengv/modules/FindEigen.cmake0000664016516101651610000000566213344612246015322 0ustar dimadima# - Try to find Eigen3 lib # # This module supports requiring a minimum version, e.g. you can do # find_package(Eigen3 3.1.2) # to require version 3.1.2 or newer of Eigen3. # # Once done this will define # # EIGEN_FOUND - system has eigen lib with correct version # EIGEN_INCLUDE_DIR - the eigen include directory # EIGEN_VERSION - eigen version # Copyright (c) 2006, 2007 Montel Laurent, # Copyright (c) 2008, 2009 Gael Guennebaud, # Copyright (c) 2009 Benoit Jacob # Redistribution and use is allowed according to the terms of the 2-clause BSD license. if(NOT Eigen_FIND_VERSION) if(NOT Eigen_FIND_VERSION_MAJOR) set(Eigen_FIND_VERSION_MAJOR 2) endif(NOT Eigen_FIND_VERSION_MAJOR) if(NOT Eigen_FIND_VERSION_MINOR) set(Eigen_FIND_VERSION_MINOR 91) endif(NOT Eigen_FIND_VERSION_MINOR) if(NOT Eigen_FIND_VERSION_PATCH) set(Eigen_FIND_VERSION_PATCH 0) endif(NOT Eigen_FIND_VERSION_PATCH) set(Eigen_FIND_VERSION "${Eigen_FIND_VERSION_MAJOR}.${Eigen_FIND_VERSION_MINOR}.${Eigen_FIND_VERSION_PATCH}") endif(NOT Eigen_FIND_VERSION) macro(_eigen3_check_version) file(READ "${EIGEN_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") set(EIGEN_WORLD_VERSION "${CMAKE_MATCH_1}") string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") set(EIGEN_MAJOR_VERSION "${CMAKE_MATCH_1}") string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") set(EIGEN_MINOR_VERSION "${CMAKE_MATCH_1}") set(EIGEN_VERSION ${EIGEN_WORLD_VERSION}.${EIGEN_MAJOR_VERSION}.${EIGEN_MINOR_VERSION}) if(${EIGEN_VERSION} VERSION_LESS ${Eigen_FIND_VERSION}) set(EIGEN_VERSION_OK FALSE) else(${EIGEN_VERSION} VERSION_LESS ${Eigen_FIND_VERSION}) set(EIGEN_VERSION_OK TRUE) endif(${EIGEN_VERSION} VERSION_LESS ${Eigen_FIND_VERSION}) if(NOT EIGEN_VERSION_OK) message(STATUS "Eigen version ${EIGEN_VERSION} found in ${EIGEN_INCLUDE_DIR}, " "but at least version ${Eigen_FIND_VERSION} is required") endif(NOT EIGEN_VERSION_OK) endmacro(_eigen3_check_version) if (EIGEN_INCLUDE_DIRS) # in cache already _eigen3_check_version() set(EIGEN_FOUND ${EIGEN_VERSION_OK}) else () find_path(EIGEN_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library PATHS ${CMAKE_INSTALL_PREFIX}/include ${KDE4_INCLUDE_DIR} PATH_SUFFIXES eigen3 eigen ) if(EIGEN_INCLUDE_DIR) _eigen3_check_version() endif(EIGEN_INCLUDE_DIR) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(Eigen DEFAULT_MSG EIGEN_INCLUDE_DIR EIGEN_VERSION_OK) mark_as_advanced(EIGEN_INCLUDE_DIR) SET(EIGEN_INCLUDE_DIRS ${EIGEN_INCLUDE_DIR} CACHE PATH "The Eigen include path.") endif() opengv/test/0000775016516101651610000000000013635643413011771 5ustar dimadimaopengv/test/test_relative_pose_rotationOnly_sac.cpp0000664016516101651610000001541613635643413022013 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.1; size_t numberPoints = 100; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = Eigen::Vector3d::Zero(); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, rotation); //Create a RotationOnlySacProblem and Ransac sac::Ransac< sac_problems::relative_pose::RotationOnlySacProblem> ransac; std::shared_ptr< sac_problems::relative_pose::RotationOnlySacProblem> relposeproblem_ptr( new sac_problems::relative_pose::RotationOnlySacProblem(adapter)); ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(0); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac threshold is: " << ransac.threshold_ << std::endl; std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; // Create Lmeds sac::Lmeds< sac_problems::relative_pose::RotationOnlySacProblem> lmeds; lmeds.sac_model_ = relposeproblem_ptr; lmeds.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); lmeds.max_iterations_ = 50; //Run the experiment gettimeofday( &tic, 0 ); lmeds.computeModel(0); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the lmeds threshold is: " << lmeds.threshold_ << std::endl; std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_ << std::endl << std::endl; std::cout << "Lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/random_generators.cpp0000664016516101651610000001763113344612246016213 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include "random_generators.hpp" #include "time_measurement.hpp" #include #include using namespace Eigen; void opengv::initializeRandomSeed() { struct timeval tic; gettimeofday( &tic, 0 ); srand ( tic.tv_usec ); } Eigen::Vector3d opengv::generateRandomPoint( double maximumDepth, double minimumDepth ) { Eigen::Vector3d cleanPoint; cleanPoint[0] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; cleanPoint[1] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; cleanPoint[2] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; Eigen::Vector3d direction = cleanPoint / cleanPoint.norm(); cleanPoint = (maximumDepth-minimumDepth) * cleanPoint + minimumDepth * direction; return cleanPoint; } Eigen::Vector3d opengv::generateRandomPointPlane() { Eigen::Vector3d cleanPoint; cleanPoint[0] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; cleanPoint[1] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; cleanPoint[2] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; cleanPoint[0] = 6*cleanPoint[0]; cleanPoint[1] = 6*cleanPoint[1]; cleanPoint[2] = 2*cleanPoint[2]-6.0; return cleanPoint; } Eigen::Vector3d opengv::addNoise( double noiseLevel, Eigen::Vector3d cleanPoint ) { //compute a vector in the normal plane (based on good conditioning) Eigen::Vector3d normalVector1; if( (fabs(cleanPoint[0]) > fabs(cleanPoint[1])) && (fabs(cleanPoint[0]) > fabs(cleanPoint[2])) ) { normalVector1[1] = 1.0; normalVector1[2] = 0.0; normalVector1[0] = -cleanPoint[1]/cleanPoint[0]; } else { if( (fabs(cleanPoint[1]) > fabs(cleanPoint[0])) && (fabs(cleanPoint[1]) > fabs(cleanPoint[2])) ) { normalVector1[2] = 1.0; normalVector1[0] = 0.0; normalVector1[1] = -cleanPoint[2]/cleanPoint[1]; } else { normalVector1[0] = 1.0; normalVector1[1] = 0.0; normalVector1[2] = -cleanPoint[0]/cleanPoint[2]; } } normalVector1 = normalVector1 / normalVector1.norm(); Eigen::Vector3d normalVector2 = cleanPoint.cross(normalVector1); double noiseX = noiseLevel * (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0 / 1.4142; double noiseY = noiseLevel * (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0 / 1.4142; Eigen::Vector3d noisyPoint = 800 * cleanPoint + noiseX *normalVector1 + noiseY * normalVector2; noisyPoint = noisyPoint / noisyPoint.norm(); return noisyPoint; } Eigen::Vector3d opengv::generateRandomTranslation( double maximumParallax ) { Eigen::Vector3d translation; translation[0] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; translation[1] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; translation[2] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0; return maximumParallax * translation; } Eigen::Vector3d opengv::generateRandomDirectionTranslation( double parallax ) { Eigen::Matrix3d rotation = generateRandomRotation(); Eigen::Vector3d translation; translation << 1.0, 0.0, 0.0; translation = rotation * translation; translation = parallax * translation; return translation; } Eigen::Matrix3d opengv::generateRandomRotation( double maxAngle ) { Eigen::Vector3d rpy; rpy[0] = ((double) rand())/ ((double) RAND_MAX); rpy[1] = ((double) rand())/ ((double) RAND_MAX); rpy[2] = ((double) rand())/ ((double) RAND_MAX); rpy[0] = maxAngle*2.0*(rpy[0]-0.5); rpy[1] = maxAngle*2.0*(rpy[1]-0.5); rpy[2] = maxAngle*2.0*(rpy[2]-0.5); Eigen::Matrix3d R1; R1(0,0) = 1.0; R1(0,1) = 0.0; R1(0,2) = 0.0; R1(1,0) = 0.0; R1(1,1) = cos(rpy[0]); R1(1,2) = -sin(rpy[0]); R1(2,0) = 0.0; R1(2,1) = -R1(1,2); R1(2,2) = R1(1,1); Eigen::Matrix3d R2; R2(0,0) = cos(rpy[1]); R2(0,1) = 0.0; R2(0,2) = sin(rpy[1]); R2(1,0) = 0.0; R2(1,1) = 1.0; R2(1,2) = 0.0; R2(2,0) = -R2(0,2); R2(2,1) = 0.0; R2(2,2) = R2(0,0); Eigen::Matrix3d R3; R3(0,0) = cos(rpy[2]); R3(0,1) = -sin(rpy[2]); R3(0,2) = 0.0; R3(1,0) =-R3(0,1); R3(1,1) = R3(0,0); R3(1,2) = 0.0; R3(2,0) = 0.0; R3(2,1) = 0.0; R3(2,2) = 1.0; Eigen::Matrix3d rotation = R3 * R2 * R1; rotation.col(0) = rotation.col(0) / rotation.col(0).norm(); rotation.col(2) = rotation.col(0).cross(rotation.col(1)); rotation.col(2) = rotation.col(2) / rotation.col(2).norm(); rotation.col(1) = rotation.col(2).cross(rotation.col(0)); rotation.col(1) = rotation.col(1) / rotation.col(1).norm(); return rotation; } Eigen::Matrix3d opengv::generateRandomRotation() { Eigen::Vector3d rpy; rpy[0] = ((double) rand())/ ((double) RAND_MAX); rpy[1] = ((double) rand())/ ((double) RAND_MAX); rpy[2] = ((double) rand())/ ((double) RAND_MAX); rpy[0] = 2*M_PI*(rpy[0]-0.5); rpy[1] = M_PI*(rpy[1]-0.5); rpy[2] = 2*M_PI*(rpy[2]-0.5); Eigen::Matrix3d R1; R1(0,0) = 1.0; R1(0,1) = 0.0; R1(0,2) = 0.0; R1(1,0) = 0.0; R1(1,1) = cos(rpy[0]); R1(1,2) = -sin(rpy[0]); R1(2,0) = 0.0; R1(2,1) = -R1(1,2); R1(2,2) = R1(1,1); Eigen::Matrix3d R2; R2(0,0) = cos(rpy[1]); R2(0,1) = 0.0; R2(0,2) = sin(rpy[1]); R2(1,0) = 0.0; R2(1,1) = 1.0; R2(1,2) = 0.0; R2(2,0) = -R2(0,2); R2(2,1) = 0.0; R2(2,2) = R2(0,0); Eigen::Matrix3d R3; R3(0,0) = cos(rpy[2]); R3(0,1) = -sin(rpy[2]); R3(0,2) = 0.0; R3(1,0) =-R3(0,1); R3(1,1) = R3(0,0); R3(1,2) = 0.0; R3(2,0) = 0.0; R3(2,1) = 0.0; R3(2,2) = 1.0; Eigen::Matrix3d rotation = R3 * R2 * R1; rotation.col(0) = rotation.col(0) / rotation.col(0).norm(); rotation.col(2) = rotation.col(0).cross(rotation.col(1)); rotation.col(2) = rotation.col(2) / rotation.col(2).norm(); rotation.col(1) = rotation.col(2).cross(rotation.col(0)); rotation.col(1) = rotation.col(1) / rotation.col(1).norm(); return rotation; } opengv/test/test_eigensolver_sac.cpp0000664016516101651610000001565213635643413016715 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.1; size_t numberPoints = 100; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomDirectionTranslation(0.1); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, rotation); //Create an EigensolverSacProblem and Ransac //The number of samples can be configured sac::Ransac< sac_problems::relative_pose::EigensolverSacProblem> ransac; std::shared_ptr< sac_problems::relative_pose::EigensolverSacProblem> eigenproblem_ptr( new sac_problems::relative_pose::EigensolverSacProblem(adapter,10)); ransac.sac_model_ = eigenproblem_ptr; ransac.threshold_ = 1.0; ransac.max_iterations_ = 100; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //do final polishing of the model over all inliers sac_problems::relative_pose::EigensolverSacProblem::model_t optimizedModel; eigenproblem_ptr->optimizeModelCoefficients( ransac.inliers_, ransac.model_coefficients_, optimizedModel); //print the results std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_.rotation << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; std::cout << "the optimized result is: " << std::endl; std::cout << optimizedModel.rotation << std::endl; // Create Lmeds sac::Lmeds lmeds; lmeds.sac_model_ = eigenproblem_ptr; lmeds.threshold_ = 1.0; lmeds.max_iterations_ = 50; //Run the experiment gettimeofday( &tic, 0 ); lmeds.computeModel(); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_.rotation << std::endl << std::endl; std::cout << "lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/test_absolute_pose_sac.cpp0000664016516101651610000001437413635643413017237 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.0; double outlierFraction = 0.1; size_t numberPoints = 100; //create a random viewpoint pose translation_t position = generateRandomTranslation(2.0); rotation_t rotation = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors; points_t points; std::vector camCorrespondences; //unused in the central case! Eigen::MatrixXd gt(3,numberPoints); generateRandom2D3DCorrespondences( position, rotation, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors, points, camCorrespondences, gt ); //print the experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central absolute adapter absolute_pose::CentralAbsoluteAdapter adapter( bearingVectors, points, rotation); //Create an AbsolutePoseSac problem and Ransac //The method can be set to KNEIP, GAO or EPNP sac::Ransac ransac; std::shared_ptr< sac_problems::absolute_pose::AbsolutePoseSacProblem> absposeproblem_ptr( new sac_problems::absolute_pose::AbsolutePoseSacProblem( adapter, sac_problems::absolute_pose::AbsolutePoseSacProblem::KNEIP)); ransac.sac_model_ = absposeproblem_ptr; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; // Create LMedS sac::Lmeds lmeds; lmeds.sac_model_ = absposeproblem_ptr; lmeds.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); lmeds.max_iterations_ = 50; //Run the LMedS experiment gettimeofday( &tic, 0 ); lmeds.computeModel(); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_ << std::endl << std::endl; std::cout << "Lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/test_noncentral_relative_pose_sac.cpp0000664016516101651610000001602613635643413021453 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.3; double outlierFraction = 0.3; size_t numberPoints = 100; int numberCameras = 4; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateRandomCameraSystem( numberCameras, camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; std::vector camCorrespondences2; Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create non-central relative adapter relative_pose::NoncentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, camOffsets, camRotations, position, rotation); //Create a NoncentralRelativePoseSacProblem and Ransac sac::Ransac< sac_problems::relative_pose::NoncentralRelativePoseSacProblem> ransac; std::shared_ptr< sac_problems::relative_pose::NoncentralRelativePoseSacProblem> relposeproblem_ptr( new sac_problems::relative_pose::NoncentralRelativePoseSacProblem( adapter, sac_problems::relative_pose::NoncentralRelativePoseSacProblem::SIXPT)); ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 10000; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac threshold is: " << ransac.threshold_ << std::endl; std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; // Create LMedS sac::Lmeds< sac_problems::relative_pose::NoncentralRelativePoseSacProblem> lmeds; lmeds.sac_model_ = relposeproblem_ptr; lmeds.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); lmeds.max_iterations_ = 10000; //Run the experiment gettimeofday( &tic, 0 ); lmeds.computeModel(); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the lmeds threshold is: " << lmeds.threshold_ << std::endl; std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_ << std::endl << std::endl; std::cout << "lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/test_relative_pose_rotationOnly.cpp0000664016516101651610000001444213344612246021160 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.0; double outlierFraction = 0.0; size_t numberPoints = 10; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = Eigen::Vector3d::Zero(); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, rotation); //timer struct timeval tic; struct timeval toc; size_t iterations = 100; //run experiment std::cout << "running twopt_rotationOnly (using first 2 correpondences"; std::cout << std::endl; rotation_t twopt_rotationOnly_rotation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) twopt_rotationOnly_rotation = relative_pose::twopt_rotationOnly(adapter); gettimeofday( &toc, 0 ); double twopt_rotationOnly_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running rotationOnly (using all correspondences)" << std::endl; rotation_t rotationOnly_rotation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) rotationOnly_rotation = relative_pose::rotationOnly(adapter); gettimeofday( &toc, 0 ); double rotationOnly_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running rotationOnly with 10 correspondences" << std::endl; std::vector indices10 = getNindices(10); rotation_t rotationOnly10_rotation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) rotationOnly10_rotation = relative_pose::rotationOnly(adapter,indices10); gettimeofday( &toc, 0 ); double rotationOnly10_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; //print results std::cout << "results from two-points rotation algorithm:" << std::endl; std::cout << twopt_rotationOnly_rotation << std::endl << std::endl; std::cout << "results from rotation algorithm:" << std::endl; std::cout << rotationOnly_rotation << std::endl << std::endl; std::cout << "results from rotation algorithm with 10 points:" << std::endl; std::cout << rotationOnly10_rotation << std::endl << std::endl; std::cout << "timings from two-points rotation algorithm: "; std::cout << twopt_rotationOnly_time << std::endl; std::cout << "timings from rotation algorithm: "; std::cout << rotationOnly_time << std::endl; std::cout << "timings from rotation algorithm with 10 points: "; std::cout << rotationOnly10_time << std::endl; } opengv/test/test_point_cloud.cpp0000664016516101651610000001515013344612246016052 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.05; double outlierFraction = 0.0; size_t numberPoints = 10; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //derive the correspondences based on random point-cloud points_t points1; points_t points2; Eigen::MatrixXd gt(3,numberPoints); generateRandom3D3DCorrespondences( position1, rotation1, position2, rotation2, numberPoints, noise, outlierFraction, points1, points2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create the point-cloud adapter point_cloud::PointCloudAdapter adapter( points1, points2, position, rotation); //timer struct timeval tic; struct timeval toc; size_t iterations = 100; //run experiments std::cout << "running threept with all the points" << std::endl; transformation_t threept_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) threept_transformation = point_cloud::threept_arun(adapter); gettimeofday( &toc, 0 ); double threept_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running threept with three points only" << std::endl; std::vector indices3 = getNindices(3); transformation_t threept_transformation_3; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) threept_transformation_3 = point_cloud::threept_arun(adapter,indices3); gettimeofday( &toc, 0 ); double threept_time_3 = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization" << std::endl; //add a small perturbation to the rotation translation_t t_perturbed; rotation_t R_perturbed; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1); adapter.sett12(t_perturbed); adapter.setR12(R_perturbed); transformation_t nonlinear_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) nonlinear_transformation = point_cloud::optimize_nonlinear(adapter); gettimeofday( &toc, 0 ); double nonlinear_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization with three points only"; std::cout << std::endl; //add a small perturbation to the rotation getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.01); adapter.sett12(t_perturbed); adapter.setR12(R_perturbed); transformation_t nonlinear_transformation_3 = point_cloud::optimize_nonlinear(adapter,indices3); //print results std::cout << "results from threept_arun algorithm:" << std::endl; std::cout << threept_transformation << std::endl << std::endl; std::cout << "results from threept_arun with 3 points only:" << std::endl; std::cout << threept_transformation_3 << std::endl << std::endl; std::cout << "results of nonlinear optimization:" << std::endl; std::cout << nonlinear_transformation << std::endl << std::endl; std::cout << "results of nonlinear optimization with 3 points only:" << std::endl; std::cout << nonlinear_transformation_3 << std::endl << std::endl; std::cout << "timings from threept_arun algorithm: "; std::cout << threept_time << std::endl; std::cout << "timings from threept_arun algorithm with 3 points only: "; std::cout << threept_time_3 << std::endl; std::cout << "timing of nonlinear optimization: "; std::cout << nonlinear_time << std::endl; } opengv/test/test_multi_noncentral_absolute_pose_sac.cpp0000664016516101651610000001305113344612246022660 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.1; size_t pointsPerCam = 25; int numberCameras = 4; //create a random viewpoint pose translation_t position = generateRandomTranslation(2.0); rotation_t rotation = generateRandomRotation(0.5); //create a random camera-system translations_t camOffsets; rotations_t camRotations; generateRandomCameraSystem( numberCameras, camOffsets, camRotations ); //derive correspondences based on random point-cloud std::vector > multiPoints; std::vector > multiBearingVectors; std::vector< std::shared_ptr > gt; generateMulti2D3DCorrespondences( position, rotation, camOffsets, camRotations, pointsPerCam, noise, outlierFraction, multiPoints, multiBearingVectors, gt ); //print the experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a non-central absolute adapter absolute_pose::NoncentralAbsoluteMultiAdapter adapter( multiBearingVectors, multiPoints, camOffsets, camRotations ); //Create a AbsolutePoseSacProblem and Ransac //The method is set to GP3P sac::MultiRansac< sac_problems::absolute_pose::MultiNoncentralAbsolutePoseSacProblem> ransac; std::shared_ptr< sac_problems::absolute_pose::MultiNoncentralAbsolutePoseSacProblem> absposeproblem_ptr( new sac_problems::absolute_pose::MultiNoncentralAbsolutePoseSacProblem( adapter )); ransac.sac_model_ = absposeproblem_ptr; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; size_t numberInliers = 0; for(size_t i = 0; i < ransac.inliers_.size(); i++) numberInliers += ransac.inliers_[i].size(); std::cout << "the number of inliers is: " << numberInliers; std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) { for(size_t j = 0; j < ransac.inliers_[i].size(); j++) std::cout << ransac.inliers_[i][j] << " "; } std::cout << std::endl << std::endl; } opengv/test/test_noncentral_relative_pose.cpp0000664016516101651610000002062513344612246020622 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.0; double outlierFraction = 0.0; size_t numberPoints = 100; int numberCameras = 4; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateRandomCameraSystem( numberCameras, camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; std::vector camCorrespondences2; Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create non-central relative adapter relative_pose::NoncentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, camOffsets, camRotations, position, rotation); //timer struct timeval tic; struct timeval toc; size_t iterations = 100; //running experiment std::cout << "running sixpt with 6 correspondences" << std::endl; std::vector indices6 = getNindices(6); rotations_t sixpt_rotations; gettimeofday( &tic, 0 ); for( size_t i = 0; i < iterations; i++ ) sixpt_rotations = relative_pose::sixpt(adapter,indices6); gettimeofday( &toc, 0 ); double sixpt_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running ge with 8 correspondences" << std::endl; std::vector indices8 = getNindices(8); rotation_t ge_rotation; gettimeofday( &tic, 0 ); for( size_t i = 0; i < iterations; i++ ) ge_rotation = relative_pose::ge(adapter,indices8); gettimeofday( &toc, 0 ); double ge_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running seventeenpt algorithm with 17 correspondences"; std::cout << std::endl; std::vector indices17 = getNindices(17); transformation_t seventeenpt_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) seventeenpt_transformation = relative_pose::seventeenpt(adapter,indices17); gettimeofday( &toc, 0 ); double seventeenpt_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running seventeenpt algorithm with all correspondences"; std::cout << std::endl; transformation_t seventeenpt_transformation_all; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) seventeenpt_transformation_all = relative_pose::seventeenpt(adapter); gettimeofday( &toc, 0 ); double seventeenpt_time_all = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization" << std::endl; translation_t t_perturbed; rotation_t R_perturbed; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1); transformation_t nonlinear_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) { adapter.sett12(t_perturbed); adapter.setR12(R_perturbed); nonlinear_transformation = relative_pose::optimize_nonlinear(adapter); } gettimeofday( &toc, 0 ); double nonlinear_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization with 10 correspondences"; std::cout << std::endl; std::vector indices10 = getNindices(10); getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1); adapter.sett12(t_perturbed); adapter.setR12(R_perturbed); transformation_t nonlinear_transformation_10 = relative_pose::optimize_nonlinear(adapter,indices10); //print results std::cout << "results from 6pt algorithm:" << std::endl; for( size_t i = 0; i < sixpt_rotations.size(); i++ ) std::cout << sixpt_rotations[i] << std::endl << std::endl; std::cout << "result from ge using 8 points:" << std::endl; std::cout << ge_rotation << std::endl << std::endl; std::cout << "results from 17pt algorithm:" << std::endl; std::cout << seventeenpt_transformation << std::endl << std::endl; std::cout << "results from 17pt algorithm with all points:" << std::endl; std::cout << seventeenpt_transformation_all << std::endl << std::endl; std::cout << "results from nonlinear algorithm:" << std::endl; std::cout << nonlinear_transformation << std::endl << std::endl; std::cout << "results from nonlinear algorithm with only few correspondences:"; std::cout << std::endl; std::cout << nonlinear_transformation_10 << std::endl << std::endl; std::cout << "timings from 6pt algorithm: "; std::cout << sixpt_time << std::endl; std::cout << "timings from ge: "; std::cout << ge_time << std::endl; std::cout << "timings from 17pt algorithm: "; std::cout << seventeenpt_time << std::endl; std::cout << "timings from 17pt algorithm with all the points: "; std::cout << seventeenpt_time_all << std::endl; std::cout << "timings from nonlinear algorithm: "; std::cout << nonlinear_time << std::endl; } opengv/test/test_relative_pose_sac.cpp0000664016516101651610000001713413635643413017231 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.1; size_t numberPoints = 100; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //compute and print the essential-matrix printEssentialMatrix( position, rotation ); //create a central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, rotation); //Create a RelativePoseSac problem and Ransac //Set algorithm to NISTER, STEWENIUS, SEVENPT, or EIGHTPT sac::Ransac< sac_problems::relative_pose::CentralRelativePoseSacProblem> ransac; std::shared_ptr< sac_problems::relative_pose::CentralRelativePoseSacProblem> relposeproblem_ptr( new sac_problems::relative_pose::CentralRelativePoseSacProblem( adapter, sac_problems::relative_pose::CentralRelativePoseSacProblem::STEWENIUS)); ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print results for ransac 1 std::cout << "the ransac threshold is: " << ransac.threshold_ << std::endl; std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "the normalized translation is: " << std::endl; std::cout << ransac.model_coefficients_.col(3)/ ransac.model_coefficients_.col(3).norm() << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; // Create Lmeds sac::Lmeds< sac_problems::relative_pose::CentralRelativePoseSacProblem> lmeds; lmeds.sac_model_ = relposeproblem_ptr; lmeds.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); lmeds.max_iterations_ = 50; //Run the experiment gettimeofday( &tic, 0 ); lmeds.computeModel(); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print results std::cout << "the lmeds threshold is: " << lmeds.threshold_ << std::endl; std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_ << std::endl << std::endl; std::cout << "the normalized translation is: " << std::endl; std::cout << lmeds.model_coefficients_.col(3)/ lmeds.model_coefficients_.col(3).norm() << std::endl << std::endl; std::cout << "Lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/random_generators.hpp0000664016516101651610000000566613344612246016225 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RANDOM_GENERATORS_HPP_ #define OPENGV_RANDOM_GENERATORS_HPP_ #include #include #include namespace opengv { void initializeRandomSeed(); Eigen::Vector3d generateRandomPoint( double maximumDepth, double minimumDepth ); Eigen::Vector3d generateRandomPointPlane(); Eigen::Vector3d addNoise( double noiseLevel, Eigen::Vector3d cleanPoint ); Eigen::Vector3d generateRandomTranslation( double maximumParallax ); Eigen::Vector3d generateRandomDirectionTranslation( double parallax ); Eigen::Matrix3d generateRandomRotation( double maxAngle ); Eigen::Matrix3d generateRandomRotation(); } #endif /* OPENGV_RANDOM_GENERATORS_HPP_ */ opengv/test/test_Sturm.cpp0000664016516101651610000001305713344612246014651 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { std::vector coeffs; coeffs.push_back(1.0); coeffs.push_back(4.0); coeffs.push_back(1.0); coeffs.push_back(-6.0); //timer struct timeval tic; struct timeval toc; size_t iterations = 50; //for now just construct the problem gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) math::Sturm sturm(coeffs); gettimeofday( &toc, 0 ); double time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "the initialization takes " << time << " seconds" << std::endl; math::Sturm sturm(coeffs); //test the lagrangian bounds gettimeofday( &tic, 0 ); double bound; for(size_t i = 0; i < iterations; i++) bound = sturm.computeLagrangianBound(); gettimeofday( &toc, 0 ); time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "the initial bound computation takes " << time << " seconds" << std::endl; std::cout << "the bound evaluates to " << bound << std::endl; //now evaluate the chain to verify that the number of roots is 3 gettimeofday( &tic, 0 ); size_t numberRoots; for(size_t i = 0; i < iterations; i++) numberRoots = sturm.evaluateChain(-bound) - sturm.evaluateChain(bound); gettimeofday( &toc, 0 ); time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "the evaluation of two bounds takes " << time << " seconds" << std::endl; std::cout << "the obtained number of roots is " << numberRoots << std::endl; //now test the bracketing mechanism gettimeofday( &tic, 0 ); std::vector roots; for(size_t i = 0; i < iterations; i++) { roots.clear(); sturm.bracketRoots(roots,0.5); } gettimeofday( &toc, 0 ); time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "the bracketing of the roots took " << time << " seconds" << std::endl; std::cout << "the obtained brackets are:" << std::endl; std::vector::iterator it = roots.begin(); while( it != roots.end() ) { std::cout << "root:" << (*it) << std::endl; it++; } //now test the entire root-finding mechanism gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) roots = sturm.findRoots(); gettimeofday( &toc, 0 ); time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "the entire finding of the roots took " << time << " seconds" << std::endl; std::cout << "the obtained roots are:" << std::endl; std::vector::iterator it2 = roots.begin(); while( it2 != roots.end() ) { std::cout << (*it2) << std::endl; it2++; } //now test the new root-finding with inbuild gradient descent gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) { roots.clear(); sturm.findRoots2(roots); } gettimeofday( &toc, 0 ); time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "the entire finding of the roots took " << time << " seconds" << std::endl; std::cout << "the obtained roots are:" << std::endl; it2 = roots.begin(); while( it2 != roots.end() ) { std::cout << (*it2) << std::endl; it2++; } return 0; } opengv/test/test_multi_noncentral_relative_pose_sac.cpp0000664016516101651610000001412513344612246022660 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.3; double outlierFraction = 0.1; size_t pointsPerCam = 25; int numberCameras = 4; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateRandomCameraSystem( numberCameras, camOffsets, camRotations ); //derive correspondences based on random point-cloud std::vector > multiBearingVectors1; std::vector > multiBearingVectors2; std::vector > gt; generateMulti2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, pointsPerCam, noise, outlierFraction, multiBearingVectors1, multiBearingVectors2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a non-central relative multi-adapter relative_pose::NoncentralRelativeMultiAdapter adapter( multiBearingVectors1, multiBearingVectors2, camOffsets, camRotations); //Create a MultiNoncentralRelativePoseSacProblem and Ransac opengv::sac::MultiRansac< sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem> ransac; std::shared_ptr< sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem> relposeproblem_ptr( new sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem( adapter, sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem::SIXPT)); ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 100; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac threshold is: " << ransac.threshold_ << std::endl; std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; size_t numberInliers = 0; for(size_t i = 0; i < ransac.inliers_.size(); i++) numberInliers += ransac.inliers_[i].size(); std::cout << "the number of inliers is: " << numberInliers; std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) { for(size_t j = 0; j < ransac.inliers_[i].size(); j++) std::cout << ransac.inliers_[i][j] << " "; } std::cout << std::endl << std::endl; } opengv/test/test_noncentral_absolute_pose.cpp0000664016516101651610000002005713344612246020624 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.0; double outlierFraction = 0.0; size_t numberPoints = 100; int numberCameras = 4; //create a random viewpoint pose translation_t position = generateRandomTranslation(2.0); rotation_t rotation = generateRandomRotation(0.5); //create a random camera-system translations_t camOffsets; rotations_t camRotations; generateRandomCameraSystem( numberCameras, camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors; points_t points; std::vector camCorrespondences; Eigen::MatrixXd gt(3,numberPoints); generateRandom2D3DCorrespondences( position, rotation, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors, points, camCorrespondences, gt ); //print the experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a non-central absolute adapter absolute_pose::NoncentralAbsoluteAdapter adapter( bearingVectors, camCorrespondences, points, camOffsets, camRotations, rotation); //timer struct timeval tic; struct timeval toc; size_t iterations = 50; //run the experiments std::cout << "running Kneip's GP3P (using first three correspondences/"; std::cout << std::endl; transformations_t gp3p_transformations; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) gp3p_transformations = absolute_pose::gp3p(adapter); gettimeofday( &toc, 0 ); double gp3p_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running gpnp over all correspondences" << std::endl; transformation_t gpnp_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) gpnp_transformation = absolute_pose::gpnp(adapter); gettimeofday( &toc, 0 ); double gpnp_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running gpnp over 6 correspondences" << std::endl; std::vector indices6 = getNindices(6); transformation_t gpnp_transformation_6 = absolute_pose::gpnp( adapter, indices6 ); std::cout << "running upnp over all correspondences" << std::endl; transformations_t upnp_transformations; gettimeofday( &tic, 0 ); for( size_t i = 0; i < iterations; i++ ) upnp_transformations = absolute_pose::upnp(adapter); gettimeofday( &toc, 0); double upnp_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running upnp over 3 correspondences" << std::endl; std::vector indices3 = getNindices(3); transformations_t upnp_transformations_3 = absolute_pose::upnp( adapter, indices3 ); std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization" << std::endl; //add a small perturbation to the rotation translation_t t_perturbed; rotation_t R_perturbed; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1 ); transformation_t nonlinear_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) { adapter.sett(t_perturbed); adapter.setR(R_perturbed); nonlinear_transformation = absolute_pose::optimize_nonlinear(adapter); } gettimeofday( &toc, 0 ); double nonlinear_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization with 10 correspondences"; std::cout << std::endl; std::vector indices10 = getNindices(10); //add a small perturbation to the rotation getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1 ); adapter.sett(t_perturbed); adapter.setR(R_perturbed); transformation_t nonlinear_transformation_10 = absolute_pose::optimize_nonlinear(adapter,indices10); //print the results std::cout << "results from gp3p algorithm:" << std::endl; for(size_t i = 0; i < gp3p_transformations.size(); i++) std::cout << gp3p_transformations[i] << std::endl << std::endl; std::cout << "results from gpnp algorithm:" << std::endl; std::cout << gpnp_transformation << std::endl << std::endl; std::cout << "results from gpnp algorithm with only 6 correspondences:"; std::cout << std::endl; std::cout << gpnp_transformation_6 << std::endl << std::endl; std::cout << "results from upnp algorithm:" << std::endl; for(size_t i = 0; i < upnp_transformations.size(); i++) std::cout << upnp_transformations[i] << std::endl << std::endl; std::cout << "results from upnp algorithm with only 3 correspondences:"; std::cout << std::endl; for(size_t i = 0; i < upnp_transformations_3.size(); i++) std::cout << upnp_transformations_3[i] << std::endl << std::endl; std::cout << "results from nonlinear algorithm:" << std::endl; std::cout << nonlinear_transformation << std::endl << std::endl; std::cout << "results from nonlinear algorithm with only 10 correspondences:"; std::cout << std::endl; std::cout << nonlinear_transformation_10 << std::endl << std::endl; std::cout << "timings from gp3p algorithm: "; std::cout << gp3p_time << std::endl; std::cout << "timings from gpnp algorithm: "; std::cout << gpnp_time << std::endl; std::cout << "timings from upnp algorithm: "; std::cout << upnp_time << std::endl; std::cout << "timings from nonlinear algorithm: "; std::cout << nonlinear_time << std::endl; } opengv/test/experiment_helpers.cpp0000664016516101651610000004720113344612246016400 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include "experiment_helpers.hpp" #include "random_generators.hpp" #include #include #include void opengv::generateCentralCameraSystem( translations_t & camOffsets, rotations_t & camRotations ) { //create a fake camera system for a central camera camOffsets.push_back(Eigen::Vector3d::Zero()); camRotations.push_back(Eigen::Matrix3d::Identity()); } void opengv::generateRandomCameraSystem( int numberCameras, translations_t & camOffsets, rotations_t & camRotations ) { double offset = 0.5; //this is the distance from the viewpoint origin for( int i = 0; i < numberCameras; i++ ) { translation_t camOffset = generateRandomDirectionTranslation(offset); rotation_t camRotation = generateRandomRotation(); camOffsets.push_back(camOffset); camRotations.push_back(camRotation); } } void opengv::extractRelativePose( const translation_t & position1, const translation_t & position2, const rotation_t & rotation1, const rotation_t & rotation2, translation_t & relativePosition, rotation_t & relativeRotation, bool normalize ) { relativeRotation = rotation1.transpose() * rotation2; relativePosition = rotation1.transpose() * (position2 - position1); if(normalize) relativePosition = relativePosition / relativePosition.norm(); } void opengv::printExperimentCharacteristics( const translation_t & position, const rotation_t & rotation, double noise, double outlierFraction ) { std::cout << "the random position is:" << std::endl; std::cout << position << std::endl << std::endl; std::cout << "the random rotation is:" << std::endl; std::cout << rotation << std::endl << std::endl; std::cout << "the noise in the data is:" << std::endl; std::cout << noise << std::endl; std::cout << "the outlier fraction is:" << std::endl; std::cout << outlierFraction << std::endl; } void opengv::printBearingVectorArraysMatlab( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2 ) { size_t numberBearingVectors = bearingVectors1.size(); //temp: print the vectors in matlab format (for debugging purposes) size_t precision = 10; std::cout << "ov1 = ["; for( size_t i = 0; i < numberBearingVectors; i++ ) std::cout << std::setprecision(precision) << bearingVectors1[i](0,0) << " "; std::cout << ";" << std::endl; for( size_t i = 0; i < 8; i++ ) std::cout << std::setprecision(precision) << bearingVectors1[i](1,0) << " "; std::cout << ";" << std::endl; for( size_t i = 0; i < 8; i++ ) std::cout << std::setprecision(precision) << bearingVectors1[i](2,0) << " "; std::cout << "];" << std::endl; std::cout << "ov2 = ["; for( size_t i = 0; i < 8; i++ ) std::cout << std::setprecision(precision) << bearingVectors2[i](0,0) << " "; std::cout << ";" << std::endl; for( size_t i = 0; i < 8; i++ ) std::cout << std::setprecision(precision) << bearingVectors2[i](1,0) << " "; std::cout << ";" << std::endl; for( size_t i = 0; i < 8; i++ ) std::cout << std::setprecision(precision) << bearingVectors2[i](2,0) << " "; std::cout << "];" << std::endl; } void opengv::printEssentialMatrix( const translation_t & position, const rotation_t & rotation) { //E transforms vectors from vp 2 to 1: x_1^T * E * x_2 = 0 //and E = (t)_skew*R Eigen::Matrix3d t_skew = Eigen::Matrix3d::Zero(); t_skew(0,1) = -position[2]; t_skew(0,2) = position[1]; t_skew(1,0) = position[2]; t_skew(1,2) = -position[0]; t_skew(2,0) = -position[1]; t_skew(2,1) = position[0]; essential_t E = t_skew * rotation; double matrixNorm = 0.0; for(size_t r = 0; r < 3; r++) { for(size_t c = 0; c < 3; c++) matrixNorm += pow(E(r,c),2); } matrixNorm = sqrt(matrixNorm); for(size_t r = 0; r < 3; r++) { for(size_t c = 0; c < 3; c++) E(r,c) = E(r,c) / matrixNorm; } std::cout << "the random essential matrix is:" << std::endl; std::cout << E << std::endl; } void opengv::getPerturbedPose( const translation_t & position, const rotation_t & rotation, translation_t & perturbedPosition, rotation_t & perturbedRotation, double amplitude ) { perturbedPosition = position; cayley_t cayley = math::rot2cayley(rotation); for( size_t i = 0; i < 3; i++ ) { perturbedPosition[i] = perturbedPosition[i] + (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*amplitude; cayley[i] = cayley[i] + (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*amplitude; } perturbedRotation = math::cayley2rot(cayley); } std::vector opengv::getNindices( int n ) { std::vector indices; for(int i = 0; i < n; i++) indices.push_back(i); return indices; } void opengv::generateRandom2D3DCorrespondences( const translation_t & position, const rotation_t & rotation, const translations_t & camOffsets, const rotations_t & camRotations, size_t numberPoints, double noise, double outlierFraction, bearingVectors_t & bearingVectors, points_t & points, std::vector & camCorrespondences, Eigen::MatrixXd & gt ) { //initialize point-cloud double minDepth = 4; double maxDepth = 8; for( size_t i = 0; i < (size_t) gt.cols(); i++ ) gt.col(i) = generateRandomPoint( maxDepth, minDepth ); //create the 2D3D-correspondences by looping through the cameras size_t numberCams = camOffsets.size(); size_t camCorrespondence = 0; for( size_t i = 0; i < (size_t) gt.cols(); i++ ) { //get the camera transformation translation_t camOffset = camOffsets[camCorrespondence]; rotation_t camRotation = camRotations[camCorrespondence]; //store the point points.push_back(gt.col(i)); //project the point into the viewpoint frame point_t bodyPoint = rotation.transpose()*(gt.col(i) - position); //project the point into the camera frame bearingVectors.push_back(camRotation.transpose()*(bodyPoint - camOffset)); //normalize the bearing-vector to 1 bearingVectors[i] = bearingVectors[i] / bearingVectors[i].norm(); //add noise if( noise > 0.0 ) bearingVectors[i] = addNoise(noise,bearingVectors[i]); //push back the camera correspondence camCorrespondences.push_back(camCorrespondence++); if(camCorrespondence > (numberCams-1) ) camCorrespondence = 0; } //add outliers //compute the number of outliers based on fraction size_t numberOutliers = (size_t) floor(outlierFraction*numberPoints); //make the first numberOutliers points be outliers for(size_t i = 0; i < numberOutliers; i++) { //extract the camera transformation translation_t camOffset = camOffsets[camCorrespondences[i]]; rotation_t camRotation = camRotations[camCorrespondences[i]]; //create random point point_t p = generateRandomPoint(8,4); //project into viewpoint frame point_t bodyPoint = rotation.transpose()*(p - position); //project into camera-frame and use as outlier measurement bearingVectors[i] = camRotation.transpose()*(bodyPoint - camOffset); //normalize the bearing vector bearingVectors[i] = bearingVectors[i] / bearingVectors[i].norm(); } } void opengv::generateMulti2D3DCorrespondences( const translation_t & position, const rotation_t & rotation, const translations_t & camOffsets, const rotations_t & camRotations, size_t pointsPerCam, double noise, double outlierFraction, std::vector > & multiPoints, std::vector > & multiBearingVectors, std::vector > & gt ) { //initialize point-cloud double minDepth = 4; double maxDepth = 8; for( size_t cam = 0; cam < camOffsets.size(); cam++ ) { std::shared_ptr gt_sub(new Eigen::MatrixXd(3,pointsPerCam)); for( size_t i = 0; i < pointsPerCam; i++ ) gt_sub->col(i) = generateRandomPoint( maxDepth, minDepth ); gt.push_back(gt_sub); } //iterate through the cameras (pairs) for( size_t cam = 0; cam < camOffsets.size(); cam++ ) { //create the bearing-vector arrays for this camera std::shared_ptr points(new points_t()); std::shared_ptr bearingVectors(new bearingVectors_t()); //get the offset and rotation of this camera translation_t camOffset = camOffsets[cam]; rotation_t camRotation = camRotations[cam]; //now iterate through the points of that camera for( size_t i = 0; i < (size_t) pointsPerCam; i++ ) { points->push_back(gt[cam]->col(i)); //project the point into the viewpoint frame point_t bodyPoint = rotation.transpose()*(gt[cam]->col(i) - position); //project that point into the camera bearingVectors->push_back( camRotation.transpose()*(bodyPoint - camOffset) ); //normalize the vector (*bearingVectors)[i] = (*bearingVectors)[i] / (*bearingVectors)[i].norm(); //add noise if( noise > 0.0 ) (*bearingVectors)[i] = addNoise(noise,(*bearingVectors)[i]); } //push back the stuff for this camera multiPoints.push_back(points); multiBearingVectors.push_back(bearingVectors); } //add outliers size_t outliersPerCam = (size_t) floor(outlierFraction*pointsPerCam); //iterate through the cameras for(size_t cam = 0; cam < camOffsets.size(); cam++) { //get the offset and rotation of this camera translation_t camOffset = camOffsets[cam]; rotation_t camRotation = camRotations[cam]; //add outliers for(size_t i = 0; i < outliersPerCam; i++) { //generate a random point point_t p = generateRandomPoint(8,4); //transform that point into viewpoint 2 only point_t bodyPoint = rotation.transpose()*(p - position); //use as measurement (outlier) (*(multiBearingVectors[cam].get()))[i] = camRotation.transpose()*(bodyPoint - camOffset); //normalize (*(multiBearingVectors[cam].get()))[i] = (*(multiBearingVectors[cam].get()))[i] / (*(multiBearingVectors[cam].get()))[i].norm(); } } } void opengv::generateRandom2D2DCorrespondences( const translation_t & position1, const rotation_t & rotation1, const translation_t & position2, const rotation_t & rotation2, const translations_t & camOffsets, const rotations_t & camRotations, size_t numberPoints, double noise, double outlierFraction, bearingVectors_t & bearingVectors1, bearingVectors_t & bearingVectors2, std::vector & camCorrespondences1, std::vector & camCorrespondences2, Eigen::MatrixXd & gt ) { //initialize point-cloud double minDepth = 4; double maxDepth = 8; for( size_t i = 0; i < (size_t) gt.cols(); i++ ) gt.col(i) = generateRandomPoint( maxDepth, minDepth ); //create the 2D3D-correspondences by looping through the cameras size_t numberCams = camOffsets.size(); size_t camCorrespondence = 0; for( size_t i = 0; i < (size_t) gt.cols(); i++ ) { //get the camera transformation translation_t camOffset = camOffsets[camCorrespondence]; rotation_t camRotation = camRotations[camCorrespondence]; //get the point in viewpoint 1 point_t bodyPoint1 = rotation1.transpose()*(gt.col(i) - position1); //get the point in viewpoint 2 point_t bodyPoint2 = rotation2.transpose()*(gt.col(i) - position2); //get the point in the camera in viewpoint 1 bearingVectors1.push_back(camRotation.transpose()*(bodyPoint1 - camOffset)); //get the point in the camera in viewpoint 2 bearingVectors2.push_back(camRotation.transpose()*(bodyPoint2 - camOffset)); //normalize the bearing-vectors bearingVectors1[i] = bearingVectors1[i] / bearingVectors1[i].norm(); bearingVectors2[i] = bearingVectors2[i] / bearingVectors2[i].norm(); //add noise if( noise > 0.0 ) { bearingVectors1[i] = addNoise(noise,bearingVectors1[i]); bearingVectors2[i] = addNoise(noise,bearingVectors2[i]); } //push back the camera correspondences camCorrespondences1.push_back(camCorrespondence); camCorrespondences2.push_back(camCorrespondence++); if(camCorrespondence > (numberCams - 1) ) camCorrespondence = 0; } //add outliers size_t numberOutliers = (size_t) floor(outlierFraction*numberPoints); for(size_t i = 0; i < numberOutliers; i++) { //get the corresponding camera transformation translation_t camOffset = camOffsets[camCorrespondence]; rotation_t camRotation = camRotations[camCorrespondence]; //create random point point_t p = generateRandomPoint(8,4); //project this point into viewpoint 2 point_t bodyPoint = rotation2.transpose()*(p - position2); //project this point into the corresponding camera in viewpoint 2 //and use as outlier bearingVectors2[i] = camRotation.transpose()*(bodyPoint - camOffset); //normalize the bearing vector bearingVectors2[i] = bearingVectors2[i] / bearingVectors2[i].norm(); } } void opengv::generateRandom3D3DCorrespondences( const translation_t & position1, const rotation_t & rotation1, const translation_t & position2, const rotation_t & rotation2, size_t numberPoints, double noise, double outlierFraction, bearingVectors_t & points1, bearingVectors_t & points2, Eigen::MatrixXd & gt ) { //initialize point-cloud double minDepth = 4; double maxDepth = 8; for( size_t i = 0; i < (size_t) gt.cols(); i++ ) gt.col(i) = generateRandomPoint( maxDepth, minDepth ); //create the 3D-3D correspondences for( size_t i = 0; i < (size_t) gt.cols(); i++ ) { //transform the points into the frames and store points1.push_back(rotation1.transpose()*(gt.col(i) - position1)); points2.push_back(rotation2.transpose()*(gt.col(i) - position2)); //add noise if( noise > 0.0 ) { points1[i] = points1[i] + generateRandomTranslation(noise); points2[i] = points2[i] + generateRandomTranslation(noise); } } //add outliers size_t numberOutliers = (size_t) floor(outlierFraction*numberPoints); for(size_t i = 0; i < numberOutliers; i++) { //generate a random point point_t p = generateRandomPoint(8,4); //push-back in frame 2 only to create outlier points2[i] = rotation2.transpose()*(p - position2); } } void opengv::generateMulti2D2DCorrespondences( const translation_t & position1, const rotation_t & rotation1, const translation_t & position2, const rotation_t & rotation2, const translations_t & camOffsets, const rotations_t & camRotations, size_t pointsPerCam, double noise, double outlierFraction, std::vector > & multiBearingVectors1, std::vector > & multiBearingVectors2, std::vector > & gt ) { //initialize point-cloud double minDepth = 4; double maxDepth = 8; for( size_t cam = 0; cam < camOffsets.size(); cam++ ) { std::shared_ptr gt_sub(new Eigen::MatrixXd(3,pointsPerCam)); for( size_t i = 0; i < pointsPerCam; i++ ) gt_sub->col(i) = generateRandomPoint( maxDepth, minDepth ); gt.push_back(gt_sub); } //iterate through the cameras (pairs) for( size_t cam = 0; cam < camOffsets.size(); cam++ ) { //create the bearing-vector arrays for this camera std::shared_ptr bearingVectors1(new bearingVectors_t()); std::shared_ptr bearingVectors2(new bearingVectors_t()); //get the offset and rotation of this camera translation_t camOffset = camOffsets[cam]; rotation_t camRotation = camRotations[cam]; //now iterate through the points of that camera for( size_t i = 0; i < (size_t) pointsPerCam; i++ ) { //project a point into both viewpoint frames point_t bodyPoint1 = rotation1.transpose()*(gt[cam]->col(i) - position1); point_t bodyPoint2 = rotation2.transpose()*(gt[cam]->col(i) - position2); //project that point into the cameras bearingVectors1->push_back( camRotation.transpose()*(bodyPoint1 - camOffset) ); bearingVectors2->push_back( camRotation.transpose()*(bodyPoint2 - camOffset) ); //normalize the vectors (*bearingVectors1)[i] = (*bearingVectors1)[i] / (*bearingVectors1)[i].norm(); (*bearingVectors2)[i] = (*bearingVectors2)[i] / (*bearingVectors2)[i].norm(); //add noise if( noise > 0.0 ) { (*bearingVectors1)[i] = addNoise(noise,(*bearingVectors1)[i]); (*bearingVectors2)[i] = addNoise(noise,(*bearingVectors2)[i]); } } //push back the stuff for this camera multiBearingVectors1.push_back(bearingVectors1); multiBearingVectors2.push_back(bearingVectors2); } //add outliers size_t outliersPerCam = (size_t) floor(outlierFraction*pointsPerCam); //iterate through the cameras for(size_t cam = 0; cam < camOffsets.size(); cam++) { //get the offset and rotation of this camera translation_t camOffset = camOffsets[cam]; rotation_t camRotation = camRotations[cam]; //add outliers for(size_t i = 0; i < outliersPerCam; i++) { //generate a random point point_t p = generateRandomPoint(8,4); //transform that point into viewpoint 2 only point_t bodyPoint = rotation2.transpose()*(p - position2); //use as measurement (outlier) (*multiBearingVectors2[cam])[i] = camRotation.transpose()*(bodyPoint - camOffset); //normalize (*multiBearingVectors2[cam])[i] = (*multiBearingVectors2[cam])[i] / (*multiBearingVectors2[cam])[i].norm(); } } } opengv/test/test_point_cloud_sac.cpp0000664016516101651610000001437513635643413016713 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.05; double outlierFraction = 0.1; size_t numberPoints = 100; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //derive the correspondences based on random point-cloud points_t points1; points_t points2; Eigen::MatrixXd gt(3,numberPoints); generateRandom3D3DCorrespondences( position1, rotation1, position2, rotation2, numberPoints, noise, outlierFraction, points1, points2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create the point-cloud adapter point_cloud::PointCloudAdapter adapter( points1, points2, position, rotation); //Create a PointCloudSacProblem and Ransac sac::Ransac< sac_problems::point_cloud::PointCloudSacProblem> ransac; std::shared_ptr< sac_problems::point_cloud::PointCloudSacProblem> relposeproblem_ptr( new sac_problems::point_cloud::PointCloudSacProblem(adapter)); ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = 0.1; ransac.max_iterations_ = 50; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(0); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac threshold is: " << ransac.threshold_ << std::endl; std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; // Create Lmeds sac::Lmeds< sac_problems::point_cloud::PointCloudSacProblem> lmeds; lmeds.sac_model_ = relposeproblem_ptr; lmeds.threshold_ = 0.1; lmeds.max_iterations_ = 50; //Run the experiment gettimeofday( &tic, 0 ); lmeds.computeModel(0); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the lmeds threshold is: " << lmeds.threshold_ << std::endl; std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_ << std::endl << std::endl; std::cout << "Lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/time_measurement.cpp0000664016516101651610000000551513344612246016043 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include "time_measurement.hpp" #ifdef WIN32 #include void gettimeofday( timeval * timeofday, int dummy) { struct timeb time; ftime(&time); timeofday->tv_sec = (int) time.time; timeofday->tv_usec = 1000 * (int) time.millitm; } #endif timeval timeval_minus( const struct timeval &t1, const struct timeval &t2 ) { timeval ret; ret.tv_sec = t1.tv_sec - t2.tv_sec; if( t1.tv_usec < t2.tv_usec ) { ret.tv_sec--; ret.tv_usec = t1.tv_usec - t2.tv_usec + 1000000; } else ret.tv_usec = t1.tv_usec - t2.tv_usec; return ret; } opengv/test/test_relative_pose.cpp0000664016516101651610000002442013344612246016374 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.0; double outlierFraction = 0.0; size_t numberPoints = 10; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //compute and print the essential-matrix printEssentialMatrix( position, rotation ); //create a central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, rotation); //timer struct timeval tic; struct timeval toc; size_t iterations = 50; //running experiments std::cout << "running twopt" << std::endl; translation_t twopt_translation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) twopt_translation = relative_pose::twopt(adapter,true); gettimeofday( &toc, 0 ); double twopt_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running fivept_stewenius" << std::endl; complexEssentials_t fivept_stewenius_essentials; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) fivept_stewenius_essentials = relative_pose::fivept_stewenius(adapter); gettimeofday( &toc, 0 ); double fivept_stewenius_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running fivept_nister" << std::endl; essentials_t fivept_nister_essentials; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) fivept_nister_essentials = relative_pose::fivept_nister(adapter); gettimeofday( &toc, 0 ); double fivept_nister_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running fivept_kneip" << std::endl; rotations_t fivept_kneip_rotations; gettimeofday( &tic, 0 ); std::vector indices5 = getNindices(5); for(size_t i = 0; i < iterations; i++) fivept_kneip_rotations = relative_pose::fivept_kneip(adapter,indices5); gettimeofday( &toc, 0 ); double fivept_kneip_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running sevenpt" << std::endl; essentials_t sevenpt_essentials; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) sevenpt_essentials = relative_pose::sevenpt(adapter); gettimeofday( &toc, 0 ); double sevenpt_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running eightpt" << std::endl; essential_t eightpt_essential; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) eightpt_essential = relative_pose::eightpt(adapter); gettimeofday( &toc, 0 ); double eightpt_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed rotation and "; std::cout << "running eigensolver" << std::endl; translation_t t_perturbed; rotation_t R_perturbed; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.01); rotation_t eigensolver_rotation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) { adapter.setR12(R_perturbed); eigensolver_rotation = relative_pose::eigensolver(adapter); } gettimeofday( &toc, 0 ); double eigensolver_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization" << std::endl; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1); transformation_t nonlinear_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) { adapter.sett12(t_perturbed); adapter.setR12(R_perturbed); nonlinear_transformation = relative_pose::optimize_nonlinear(adapter); } gettimeofday( &toc, 0 ); double nonlinear_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose and "; std::cout << "performing nonlinear optimization with 10 indices" << std::endl; std::vector indices10 = getNindices(10); getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1); adapter.sett12(t_perturbed); adapter.setR12(R_perturbed); transformation_t nonlinear_transformation_10 = relative_pose::optimize_nonlinear(adapter,indices10); //print results std::cout << "results from two-points algorithm:" << std::endl; std::cout << twopt_translation << std::endl << std::endl; std::cout << "results from stewenius' five-point algorithm:" << std::endl; for( size_t i = 0; i < fivept_stewenius_essentials.size(); i++ ) std::cout << fivept_stewenius_essentials.at(i) << std::endl << std::endl; std::cout << "results from nisters' five-point algorithm:" << std::endl; for( size_t i = 0; i < fivept_nister_essentials.size(); i++ ) std::cout << fivept_nister_essentials.at(i) << std::endl << std::endl; std::cout << "results from kneip's five-point algorithm:" << std::endl; for( size_t i = 0; i < fivept_kneip_rotations.size(); i++ ) std::cout << fivept_kneip_rotations.at(i) << std::endl << std::endl; std::cout << "results from seven-point algorithm:" << std::endl; for( size_t i = 0; i < sevenpt_essentials.size(); i++ ) std::cout << sevenpt_essentials.at(i) << std::endl << std::endl; std::cout << "results from eight-point algorithm:" << std::endl; std::cout << eightpt_essential << std::endl << std::endl; std::cout << "results from eigensystem based rotation solver:" << std::endl; std::cout << eigensolver_rotation << std::endl << std::endl << std::endl; std::cout << "results from nonlinear algorithm:" << std::endl; std::cout << nonlinear_transformation << std::endl << std::endl; std::cout << "results from nonlinear algorithm with only few correspondences:"; std::cout << std::endl; std::cout << nonlinear_transformation_10 << std::endl << std::endl; std::cout << "timings from two-points algorithm: "; std::cout << twopt_time << std::endl; std::cout << "timings from stewenius' five-point algorithm: "; std::cout << fivept_stewenius_time << std::endl; std::cout << "timings from nisters' five-point algorithm: "; std::cout << fivept_nister_time << std::endl; std::cout << "timings from kneip's five-point algorithm: "; std::cout << fivept_kneip_time << std::endl; std::cout << "timings from seven-point algorithm: "; std::cout << sevenpt_time << std::endl; std::cout << "timings from eight-point algorithm: "; std::cout << eightpt_time << std::endl; std::cout << "timings from eigensystem based rotation solver: "; std::cout << eigensolver_time << std::endl; std::cout << "timings from nonlinear algorithm: "; std::cout << nonlinear_time << std::endl; } opengv/test/time_measurement.hpp0000664016516101651610000000541613344612246016050 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_TIME_MEASUREMENT_HPP_ #define OPENGV_TIME_MEASUREMENT_HPP_ #include #include #ifdef WIN32 struct timeval { int tv_sec; int tv_usec; }; void gettimeofday( timeval * timeofday, int dummy); #else #include #endif #define TIMETODOUBLE(x) ( x.tv_sec + x.tv_usec * 1e-6 ) timeval timeval_minus( const struct timeval &t1, const struct timeval &t2 ); #endif /* OPENGV_TIME_MEASUREMENT_HPP_ */ opengv/test/test_triangulation.cpp0000664016516101651610000001445313344612246016420 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.0; size_t numberPoints = 10; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomTranslation(2.0); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); std::cout << "the original points are: " << std::endl << gt; std::cout << std::endl << std::endl; //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation, false ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central relative adapter and pass the relative pose relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, position, rotation); //timer struct timeval tic; struct timeval toc; size_t iterations = 100; //run experiments std::cout << "running triangulation algorithm 1" << std::endl << std::endl; double triangulate_time; MatrixXd triangulate_results(3,numberPoints); for(size_t j = 0; j < numberPoints; j++) { gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) triangulate_results.block<3,1>(0,j) = triangulation::triangulate(adapter,j); gettimeofday( &toc, 0 ); triangulate_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; } std::cout << "timing: " << triangulate_time << std::endl; std::cout << "triangulation result: " << std::endl; std::cout << triangulate_results << std::endl; MatrixXd error(1,numberPoints); for(size_t i = 0; i < numberPoints; i++) { Vector3d singleError = triangulate_results.col(i) - gt.col(i); error(0,i) = singleError.norm(); } std::cout << "triangulation error is: " << std::endl; std::cout << error << std::endl << std::endl; std::cout << "running triangulation algorithm 2" << std::endl << std::endl; double triangulate2_time; MatrixXd triangulate2_results(3,numberPoints); for(size_t j = 0; j < numberPoints; j++) { gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) triangulate2_results.block<3,1>(0,j) = triangulation::triangulate2(adapter,j); gettimeofday( &toc, 0 ); triangulate2_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; } std::cout << "timing: " << triangulate2_time << std::endl; std::cout << "triangulation result: " << std::endl; std::cout << triangulate2_results << std::endl; for(size_t i = 0; i < numberPoints; i++) { Vector3d singleError = triangulate2_results.col(i) - gt.col(i); error(0,i) = singleError.norm(); } std::cout << "triangulation error is: " << std::endl << error << std::endl; } opengv/test/experiment_helpers.hpp0000664016516101651610000001337713344612246016414 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_EXPERIMENT_HELPERS_HPP_ #define OPENGV_EXPERIMENT_HELPERS_HPP_ #include #include namespace opengv { void generateCentralCameraSystem( translations_t & camOffsets, rotations_t & camRotations ); void generateRandomCameraSystem( int numberCameras, translations_t & camOffsets, rotations_t & camRotations ); void extractRelativePose( const translation_t & position1, const translation_t & position2, const rotation_t & rotation1, const rotation_t & rotation2, translation_t & relativePosition, rotation_t & relativeRotation, bool normalize = true ); void printExperimentCharacteristics( const translation_t & position, const rotation_t & rotation, double noise, double outlierFraction ); void printBearingVectorArraysMatlab( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2 ); void printEssentialMatrix( const translation_t & position, const rotation_t & rotation); void getPerturbedPose( const translation_t & position, const rotation_t & rotation, translation_t & perturbedPosition, rotation_t & perturbedRotation, double amplitude ); std::vector getNindices( int n ); void generateRandom2D3DCorrespondences( const translation_t & position, const rotation_t & rotation, const translations_t & camOffsets, const rotations_t & camRotations, size_t numberPoints, double noise, double outlierFraction, bearingVectors_t & bearingVectors, points_t & points, std::vector & camCorrespondences, Eigen::MatrixXd & gt ); void generateMulti2D3DCorrespondences( const translation_t & position, const rotation_t & rotation, const translations_t & camOffsets, const rotations_t & camRotations, size_t pointsPerCam, double noise, double outlierFraction, std::vector > & multiPoints, std::vector > & multiBearingVectors, std::vector > & gt ); void generateRandom2D2DCorrespondences( const translation_t & position1, const rotation_t & rotation1, const translation_t & position2, const rotation_t & rotation2, const translations_t & camOffsets, const rotations_t & camRotations, size_t numberPoints, double noise, double outlierFraction, bearingVectors_t & bearingVectors1, bearingVectors_t & bearingVectors2, std::vector & camCorrespondences1, std::vector & camCorrespondences2, Eigen::MatrixXd & gt ); void generateRandom3D3DCorrespondences( const translation_t & position1, const rotation_t & rotation1, const translation_t & position2, const rotation_t & rotation2, size_t numberPoints, double noise, double outlierFraction, bearingVectors_t & points1, bearingVectors_t & points2, Eigen::MatrixXd & gt ); void generateMulti2D2DCorrespondences( const translation_t & position1, const rotation_t & rotation1, const translation_t & position2, const rotation_t & rotation2, const translations_t & camOffsets, const rotations_t & camRotations, size_t pointsPerCam, double noise, double outlierFraction, std::vector > & multiBearingVectors1, std::vector > & multiBearingVectors2, std::vector > & gt ); } #endif /* OPENGV_EXPERIMENT_HELPERS_HPP_ */ opengv/test/test_noncentral_absolute_pose_sac.cpp0000664016516101651610000001447413635643413021463 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.1; size_t numberPoints = 100; int numberCameras = 4; //create a random viewpoint pose translation_t position = generateRandomTranslation(2.0); rotation_t rotation = generateRandomRotation(0.5); //create a random camera-system translations_t camOffsets; rotations_t camRotations; generateRandomCameraSystem( numberCameras, camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors; points_t points; std::vector camCorrespondences; Eigen::MatrixXd gt(3,numberPoints); generateRandom2D3DCorrespondences( position, rotation, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors, points, camCorrespondences, gt ); //print the experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a non-central absolute adapter absolute_pose::NoncentralAbsoluteAdapter adapter( bearingVectors, camCorrespondences, points, camOffsets, camRotations, rotation); //Create a AbsolutePoseSacProblem and Ransac //The method is set to GP3P sac::Ransac< sac_problems::absolute_pose::AbsolutePoseSacProblem> ransac; std::shared_ptr< sac_problems::absolute_pose::AbsolutePoseSacProblem> absposeproblem_ptr( new sac_problems::absolute_pose::AbsolutePoseSacProblem( adapter, sac_problems::absolute_pose::AbsolutePoseSacProblem::GP3P)); ransac.sac_model_ = absposeproblem_ptr; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; //Run the experiment struct timeval tic; struct timeval toc; gettimeofday( &tic, 0 ); ransac.computeModel(); gettimeofday( &toc, 0 ); double ransac_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the ransac results is: " << std::endl; std::cout << ransac.model_coefficients_ << std::endl << std::endl; std::cout << "Ransac needed " << ransac.iterations_ << " iterations and "; std::cout << ransac_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << ransac.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < ransac.inliers_.size(); i++) std::cout << ransac.inliers_[i] << " "; std::cout << std::endl << std::endl; // Create LMedS sac::Lmeds lmeds; lmeds.sac_model_ = absposeproblem_ptr; lmeds.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); lmeds.max_iterations_ = 50; //Run the experiment gettimeofday( &tic, 0 ); lmeds.computeModel(); gettimeofday( &toc, 0 ); double lmeds_time = TIMETODOUBLE(timeval_minus(toc,tic)); //print the results std::cout << "the lmeds results is: " << std::endl; std::cout << lmeds.model_coefficients_ << std::endl << std::endl; std::cout << "Lmeds needed " << lmeds.iterations_ << " iterations and "; std::cout << lmeds_time << " seconds" << std::endl << std::endl; std::cout << "the number of inliers is: " << lmeds.inliers_.size(); std::cout << std::endl << std::endl; std::cout << "the found inliers are: " << std::endl; for(size_t i = 0; i < lmeds.inliers_.size(); i++) std::cout << lmeds.inliers_[i] << " "; std::cout << std::endl << std::endl; } opengv/test/test_absolute_pose.cpp0000664016516101651610000002224213344612246016377 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { //initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.0; double outlierFraction = 0.0; size_t numberPoints = 100; //create a random viewpoint pose translation_t position = generateRandomTranslation(2.0); rotation_t rotation = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors; points_t points; std::vector camCorrespondences; //unused in the central case! Eigen::MatrixXd gt(3,numberPoints); generateRandom2D3DCorrespondences( position, rotation, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors, points, camCorrespondences, gt ); //print the experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central absolute adapter absolute_pose::CentralAbsoluteAdapter adapter( bearingVectors, points, rotation ); //timer struct timeval tic; struct timeval toc; size_t iterations = 50; //run the experiments std::cout << "running Kneip's P2P (first two correspondences)" << std::endl; translation_t p2p_translation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) p2p_translation = absolute_pose::p2p(adapter); gettimeofday( &toc, 0 ); double p2p_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running Kneip's P3P (first three correspondences)" << std::endl; transformations_t p3p_kneip_transformations; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) p3p_kneip_transformations = absolute_pose::p3p_kneip(adapter); gettimeofday( &toc, 0 ); double p3p_kneip_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running Gao's P3P (first three correspondences)" << std::endl; transformations_t p3p_gao_transformations; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) p3p_gao_transformations = absolute_pose::p3p_gao(adapter); gettimeofday( &toc, 0 ); double p3p_gao_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running epnp (all correspondences)" << std::endl; transformation_t epnp_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) epnp_transformation = absolute_pose::epnp(adapter); gettimeofday( &toc, 0 ); double epnp_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running epnp with 6 correspondences" << std::endl; std::vector indices6 = getNindices(6); transformation_t epnp_transformation_6 = absolute_pose::epnp( adapter, indices6 ); std::cout << "running upnp with all correspondences" << std::endl; transformations_t upnp_transformations; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) upnp_transformations = absolute_pose::upnp(adapter); gettimeofday( &toc, 0 ); double upnp_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "running upnp with 3 correspondences" << std::endl; std::vector indices3 = getNindices(3); transformations_t upnp_transformations_3 = absolute_pose::upnp( adapter, indices3 ); std::cout << "setting perturbed pose"; std::cout << "and performing nonlinear optimization" << std::endl; //add a small perturbation to the pose translation_t t_perturbed; rotation_t R_perturbed; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1 ); transformation_t nonlinear_transformation; gettimeofday( &tic, 0 ); for(size_t i = 0; i < iterations; i++) { adapter.sett(t_perturbed); adapter.setR(R_perturbed); nonlinear_transformation = absolute_pose::optimize_nonlinear(adapter); } gettimeofday( &toc, 0 ); double nonlinear_time = TIMETODOUBLE(timeval_minus(toc,tic)) / iterations; std::cout << "setting perturbed pose"; std::cout << "and performing nonlinear optimization with 10 correspondences"; std::cout << std::endl; std::vector indices10 = getNindices(10); //add a small perturbation to the pose getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.1 ); adapter.sett(t_perturbed); adapter.setR(R_perturbed); transformation_t nonlinear_transformation_10 = absolute_pose::optimize_nonlinear(adapter,indices10); //print the results std::cout << "results from P2P algorithm:" << std::endl; std::cout << p2p_translation << std::endl << std::endl; std::cout << "results from Kneip's P3P algorithm:" << std::endl; for(size_t i = 0; i < p3p_kneip_transformations.size(); i++) std::cout << p3p_kneip_transformations[i] << std::endl << std::endl; std::cout << "results from Gao's P3P algorithm:" << std::endl; for(size_t i = 0; i < p3p_gao_transformations.size(); i++) std::cout << p3p_gao_transformations[i] << std::endl << std::endl; std::cout << "results from epnp algorithm:" << std::endl; std::cout << epnp_transformation << std::endl << std::endl; std::cout << "results from epnp algorithm with only 6 correspondences:"; std::cout << std::endl; std::cout << epnp_transformation_6 << std::endl << std::endl; std::cout << "results from upnp:" << std::endl; for(size_t i = 0; i < upnp_transformations.size(); i++) std::cout << upnp_transformations[i] << std::endl << std::endl; std::cout << "results form upnp algorithm with only 3 correspondences:"; std::cout << std::endl; for(size_t i = 0; i < upnp_transformations_3.size(); i++) std::cout << upnp_transformations_3[i] << std::endl << std::endl; std::cout << "results from nonlinear algorithm:" << std::endl; std::cout << nonlinear_transformation << std::endl << std::endl; std::cout << "results from nonlinear algorithm with only 10 correspondences:"; std::cout << std::endl; std::cout << nonlinear_transformation_10 << std::endl << std::endl; std::cout << "timings from P2P algorithm: "; std::cout << p2p_time << std::endl; std::cout << "timings from Kneip's P3P algorithm: "; std::cout << p3p_kneip_time << std::endl; std::cout << "timings from Gao's P3P algorithm: "; std::cout << p3p_gao_time << std::endl; std::cout << "timings from epnp algorithm: "; std::cout << epnp_time << std::endl; std::cout << "timings for the upnp algorithm: "; std::cout << upnp_time << std::endl; std::cout << "timings from nonlinear algorithm: "; std::cout << nonlinear_time << std::endl; } opengv/test/test_eigensolver.cpp0000664016516101651610000001354713344612246016065 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include "random_generators.hpp" #include "experiment_helpers.hpp" #include "time_measurement.hpp" using namespace std; using namespace Eigen; using namespace opengv; int main( int argc, char** argv ) { // initialize random seed initializeRandomSeed(); //set experiment parameters double noise = 0.5; double outlierFraction = 0.0; size_t numberPoints = 10; //generate a random pose for viewpoint 1 translation_t position1 = Eigen::Vector3d::Zero(); rotation_t rotation1 = Eigen::Matrix3d::Identity(); //generate a random pose for viewpoint 2 translation_t position2 = generateRandomDirectionTranslation(0.0005); rotation_t rotation2 = generateRandomRotation(0.5); //create a fake central camera translations_t camOffsets; rotations_t camRotations; generateCentralCameraSystem( camOffsets, camRotations ); //derive correspondences based on random point-cloud bearingVectors_t bearingVectors1; bearingVectors_t bearingVectors2; std::vector camCorrespondences1; //unused in the central case std::vector camCorrespondences2; //unused in the central case Eigen::MatrixXd gt(3,numberPoints); generateRandom2D2DCorrespondences( position1, rotation1, position2, rotation2, camOffsets, camRotations, numberPoints, noise, outlierFraction, bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, gt ); //Extract the relative pose translation_t position; rotation_t rotation; extractRelativePose( position1, position2, rotation1, rotation2, position, rotation ); //print experiment characteristics printExperimentCharacteristics( position, rotation, noise, outlierFraction ); //create a central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, rotation); //run experiments std::cout << "running eigensolver with perturbed rotation" << std::endl; translation_t t_perturbed; rotation_t R_perturbed; getPerturbedPose( position, rotation, t_perturbed, R_perturbed, 0.01); adapter.setR12(R_perturbed); rotation_t eigensolver_rotation; eigensolverOutput_t output; output.rotation = adapter.getR12(); //transferring the initial value eigensolver_rotation = relative_pose::eigensolver(adapter,output); //print results std::cout << "results from eigensystem based rotation solver:" << std::endl; std::cout << eigensolver_rotation << std::endl << std::endl; std::cout << "the eigenvectors are: " << std::endl; std::cout << output.eigenvectors << std::endl << std::endl; std::cout << "the eigenvalues are: " << std::endl; std::cout << output.eigenvalues << std::endl << std::endl; std::cout << "the norms of the eigenvectors are: " << std::endl; std::cout << output.eigenvectors.col(0).norm() << " "; std::cout << output.eigenvectors.col(1).norm() << " "; std::cout << output.eigenvectors.col(2).norm() << std::endl << std::endl; std::cout << "the orthogongality is: " << std::endl; std::cout << output.eigenvectors.col(0).transpose()*output.eigenvectors.col(1); std::cout << " "; std::cout << output.eigenvectors.col(0).transpose()*output.eigenvectors.col(2); std::cout << " "; std::cout << output.eigenvectors.col(1).transpose()*output.eigenvectors.col(2); std::cout << std::endl << std::endl; std::cout << "the norm of the translation is: " << std::endl; std::cout << output.translation.norm() << std::endl; } opengv/Doxyfile0000664016516101651610000022373313344612246012527 0ustar dimadima# Doxyfile 1.7.6.1 # This file describes the settings to be used by the documentation system # doxygen (www.doxygen.org) for a project. # # All text after a hash (#) is considered a comment and will be ignored. # The format is: # TAG = value [value, ...] # For lists items can also be appended using: # TAG += value [value, ...] # Values that contain spaces should be placed between quotes (" "). #--------------------------------------------------------------------------- # Project related configuration options #--------------------------------------------------------------------------- # This tag specifies the encoding used for all characters in the config file # that follow. The default is UTF-8 which is also the encoding used for all # text before the first occurrence of this tag. Doxygen uses libiconv (or the # iconv built into libc) for the transcoding. See # http://www.gnu.org/software/libiconv for the list of possible encodings. DOXYFILE_ENCODING = UTF-8 # The PROJECT_NAME tag is a single word (or sequence of words) that should # identify the project. Note that if you do not use Doxywizard you need # to put quotes around the project name if it contains spaces. PROJECT_NAME = "OpenGV" # The PROJECT_NUMBER tag can be used to enter a project or revision number. # This could be handy for archiving the generated documentation or # if some version control system is used. PROJECT_NUMBER = # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer # a quick idea about the purpose of the project. Keep the description short. PROJECT_BRIEF = "A library for solving calibrated central and non-central geometric vision problems" # With the PROJECT_LOGO tag one can specify an logo or icon that is # included in the documentation. The maximum height of the logo should not # exceed 55 pixels and the maximum width should not exceed 200 pixels. # Doxygen will copy the logo to the output directory. PROJECT_LOGO = # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) # base path where the generated documentation will be put. # If a relative path is entered, it will be relative to the location # where doxygen was started. If left blank the current directory will be used. OUTPUT_DIRECTORY = "doc" # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create # 4096 sub-directories (in 2 levels) under the output directory of each output # format and will distribute the generated files over these directories. # Enabling this option can be useful when feeding doxygen a huge amount of # source files, where putting all generated files in the same directory would # otherwise cause performance problems for the file system. CREATE_SUBDIRS = NO # The OUTPUT_LANGUAGE tag is used to specify the language in which all # documentation generated by doxygen is written. Doxygen will use this # information to generate all constant output in the proper language. # The default language is English, other supported languages are: # Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, # Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, # Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English # messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, # Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak, # Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. OUTPUT_LANGUAGE = English # If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will # include brief member descriptions after the members that are listed in # the file and class documentation (similar to JavaDoc). # Set to NO to disable this. BRIEF_MEMBER_DESC = YES # If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend # the brief description of a member or function before the detailed description. # Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the # brief descriptions will be completely suppressed. REPEAT_BRIEF = YES # This tag implements a quasi-intelligent brief description abbreviator # that is used to form the text in various listings. Each string # in this list, if found as the leading text of the brief description, will be # stripped from the text and the result after processing the whole list, is # used as the annotated text. Otherwise, the brief description is used as-is. # If left blank, the following values are used ("$name" is automatically # replaced with the name of the entity): "The $name class" "The $name widget" # "The $name file" "is" "provides" "specifies" "contains" # "represents" "a" "an" "the" ABBREVIATE_BRIEF = # If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then # Doxygen will generate a detailed section even if there is only a brief # description. ALWAYS_DETAILED_SEC = NO # If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all # inherited members of a class in the documentation of that class as if those # members were ordinary class members. Constructors, destructors and assignment # operators of the base classes will not be shown. INLINE_INHERITED_MEMB = NO # If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full # path before files name in the file list and in the header files. If set # to NO the shortest path that makes the file name unique will be used. FULL_PATH_NAMES = YES # If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag # can be used to strip a user-defined part of the path. Stripping is # only done if one of the specified strings matches the left-hand part of # the path. The tag can be used to show relative paths in the file list. # If left blank the directory from which doxygen is run is used as the # path to strip. STRIP_FROM_PATH = # The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of # the path mentioned in the documentation of a class, which tells # the reader which header file to include in order to use a class. # If left blank only the name of the header file containing the class # definition is used. Otherwise one should specify the include paths that # are normally passed to the compiler using the -I flag. STRIP_FROM_INC_PATH = # If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter # (but less readable) file names. This can be useful if your file system # doesn't support long names like on DOS, Mac, or CD-ROM. SHORT_NAMES = NO # If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen # will interpret the first line (until the first dot) of a JavaDoc-style # comment as the brief description. If set to NO, the JavaDoc # comments will behave just like regular Qt-style comments # (thus requiring an explicit @brief command for a brief description.) JAVADOC_AUTOBRIEF = NO # If the QT_AUTOBRIEF tag is set to YES then Doxygen will # interpret the first line (until the first dot) of a Qt-style # comment as the brief description. If set to NO, the comments # will behave just like regular Qt-style comments (thus requiring # an explicit \brief command for a brief description.) QT_AUTOBRIEF = NO # The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen # treat a multi-line C++ special comment block (i.e. a block of //! or /// # comments) as a brief description. This used to be the default behaviour. # The new default is to treat a multi-line C++ comment block as a detailed # description. Set this tag to YES if you prefer the old behaviour instead. MULTILINE_CPP_IS_BRIEF = NO # If the INHERIT_DOCS tag is set to YES (the default) then an undocumented # member inherits the documentation from any documented member that it # re-implements. INHERIT_DOCS = YES # If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce # a new page for each member. If set to NO, the documentation of a member will # be part of the file/class/namespace that contains it. SEPARATE_MEMBER_PAGES = NO # The TAB_SIZE tag can be used to set the number of spaces in a tab. # Doxygen uses this value to replace tabs by spaces in code fragments. TAB_SIZE = 8 # This tag can be used to specify a number of aliases that acts # as commands in the documentation. An alias has the form "name=value". # For example adding "sideeffect=\par Side Effects:\n" will allow you to # put the command \sideeffect (or @sideeffect) in the documentation, which # will result in a user-defined paragraph with heading "Side Effects:". # You can put \n's in the value part of an alias to insert newlines. ALIASES = # This tag can be used to specify a number of word-keyword mappings (TCL only). # A mapping has the form "name=value". For example adding # "class=itcl::class" will allow you to use the command class in the # itcl::class meaning. TCL_SUBST = # Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C # sources only. Doxygen will then generate output that is more tailored for C. # For instance, some of the names that are used will be different. The list # of all members will be omitted, etc. OPTIMIZE_OUTPUT_FOR_C = NO # Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java # sources only. Doxygen will then generate output that is more tailored for # Java. For instance, namespaces will be presented as packages, qualified # scopes will look different, etc. OPTIMIZE_OUTPUT_JAVA = NO # Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran # sources only. Doxygen will then generate output that is more tailored for # Fortran. OPTIMIZE_FOR_FORTRAN = NO # Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL # sources. Doxygen will then generate output that is tailored for # VHDL. OPTIMIZE_OUTPUT_VHDL = NO # Doxygen selects the parser to use depending on the extension of the files it # parses. With this tag you can assign which parser to use for a given extension. # Doxygen has a built-in mapping, but you can override or extend it using this # tag. The format is ext=language, where ext is a file extension, and language # is one of the parsers supported by doxygen: IDL, Java, Javascript, CSharp, C, # C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, C++. For instance to make # doxygen treat .inc files as Fortran files (default is PHP), and .f files as C # (default is Fortran), use: inc=Fortran f=C. Note that for custom extensions # you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. EXTENSION_MAPPING = # If you use STL classes (i.e. std::string, std::vector, etc.) but do not want # to include (a tag file for) the STL sources as input, then you should # set this tag to YES in order to let doxygen match functions declarations and # definitions whose arguments contain STL classes (e.g. func(std::string); v.s. # func(std::string) {}). This also makes the inheritance and collaboration # diagrams that involve STL classes more complete and accurate. BUILTIN_STL_SUPPORT = NO # If you use Microsoft's C++/CLI language, you should set this option to YES to # enable parsing support. CPP_CLI_SUPPORT = NO # Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. # Doxygen will parse them like normal C++ but will assume all classes use public # instead of private inheritance when no explicit protection keyword is present. SIP_SUPPORT = NO # For Microsoft's IDL there are propget and propput attributes to indicate getter # and setter methods for a property. Setting this option to YES (the default) # will make doxygen replace the get and set methods by a property in the # documentation. This will only work if the methods are indeed getting or # setting a simple type. If this is not the case, or you want to show the # methods anyway, you should set this option to NO. IDL_PROPERTY_SUPPORT = YES # If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC # tag is set to YES, then doxygen will reuse the documentation of the first # member in the group (if any) for the other members of the group. By default # all members of a group must be documented explicitly. DISTRIBUTE_GROUP_DOC = NO # Set the SUBGROUPING tag to YES (the default) to allow class member groups of # the same type (for instance a group of public functions) to be put as a # subgroup of that type (e.g. under the Public Functions section). Set it to # NO to prevent subgrouping. Alternatively, this can be done per class using # the \nosubgrouping command. SUBGROUPING = YES # When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and # unions are shown inside the group in which they are included (e.g. using # @ingroup) instead of on a separate page (for HTML and Man pages) or # section (for LaTeX and RTF). INLINE_GROUPED_CLASSES = NO # When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and # unions with only public data fields will be shown inline in the documentation # of the scope in which they are defined (i.e. file, namespace, or group # documentation), provided this scope is documented. If set to NO (the default), # structs, classes, and unions are shown on a separate page (for HTML and Man # pages) or section (for LaTeX and RTF). INLINE_SIMPLE_STRUCTS = NO # When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum # is documented as struct, union, or enum with the name of the typedef. So # typedef struct TypeS {} TypeT, will appear in the documentation as a struct # with name TypeT. When disabled the typedef will appear as a member of a file, # namespace, or class. And the struct will be named TypeS. This can typically # be useful for C code in case the coding convention dictates that all compound # types are typedef'ed and only the typedef is referenced, never the tag name. TYPEDEF_HIDES_STRUCT = NO # The SYMBOL_CACHE_SIZE determines the size of the internal cache use to # determine which symbols to keep in memory and which to flush to disk. # When the cache is full, less often used symbols will be written to disk. # For small to medium size projects (<1000 input files) the default value is # probably good enough. For larger projects a too small cache size can cause # doxygen to be busy swapping symbols to and from disk most of the time # causing a significant performance penalty. # If the system has enough physical memory increasing the cache will improve the # performance by keeping more symbols in memory. Note that the value works on # a logarithmic scale so increasing the size by one will roughly double the # memory usage. The cache size is given by this formula: # 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, # corresponding to a cache size of 2^16 = 65536 symbols. SYMBOL_CACHE_SIZE = 0 # Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be # set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given # their name and scope. Since this can be an expensive process and often the # same symbol appear multiple times in the code, doxygen keeps a cache of # pre-resolved symbols. If the cache is too small doxygen will become slower. # If the cache is too large, memory is wasted. The cache size is given by this # formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0, # corresponding to a cache size of 2^16 = 65536 symbols. LOOKUP_CACHE_SIZE = 0 #--------------------------------------------------------------------------- # Build related configuration options #--------------------------------------------------------------------------- # If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in # documentation are documented, even if no documentation was available. # Private class members and static file members will be hidden unless # the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES EXTRACT_ALL = NO # If the EXTRACT_PRIVATE tag is set to YES all private members of a class # will be included in the documentation. EXTRACT_PRIVATE = NO # If the EXTRACT_STATIC tag is set to YES all static members of a file # will be included in the documentation. EXTRACT_STATIC = NO # If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) # defined locally in source files will be included in the documentation. # If set to NO only classes defined in header files are included. EXTRACT_LOCAL_CLASSES = YES # This flag is only useful for Objective-C code. When set to YES local # methods, which are defined in the implementation section but not in # the interface are included in the documentation. # If set to NO (the default) only methods in the interface are included. EXTRACT_LOCAL_METHODS = NO # If this flag is set to YES, the members of anonymous namespaces will be # extracted and appear in the documentation as a namespace called # 'anonymous_namespace{file}', where file will be replaced with the base # name of the file that contains the anonymous namespace. By default # anonymous namespaces are hidden. EXTRACT_ANON_NSPACES = NO # If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all # undocumented members of documented classes, files or namespaces. # If set to NO (the default) these members will be included in the # various overviews, but no documentation section is generated. # This option has no effect if EXTRACT_ALL is enabled. HIDE_UNDOC_MEMBERS = NO # If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all # undocumented classes that are normally visible in the class hierarchy. # If set to NO (the default) these classes will be included in the various # overviews. This option has no effect if EXTRACT_ALL is enabled. HIDE_UNDOC_CLASSES = NO # If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all # friend (class|struct|union) declarations. # If set to NO (the default) these declarations will be included in the # documentation. HIDE_FRIEND_COMPOUNDS = NO # If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any # documentation blocks found inside the body of a function. # If set to NO (the default) these blocks will be appended to the # function's detailed documentation block. HIDE_IN_BODY_DOCS = NO # The INTERNAL_DOCS tag determines if documentation # that is typed after a \internal command is included. If the tag is set # to NO (the default) then the documentation will be excluded. # Set it to YES to include the internal documentation. INTERNAL_DOCS = NO # If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate # file names in lower-case letters. If set to YES upper-case letters are also # allowed. This is useful if you have classes or files whose names only differ # in case and if your file system supports case sensitive file names. Windows # and Mac users are advised to set this option to NO. CASE_SENSE_NAMES = YES # If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen # will show members with their full class and namespace scopes in the # documentation. If set to YES the scope will be hidden. HIDE_SCOPE_NAMES = NO # If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen # will put a list of the files that are included by a file in the documentation # of that file. SHOW_INCLUDE_FILES = YES # If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen # will list include files with double quotes in the documentation # rather than with sharp brackets. FORCE_LOCAL_INCLUDES = NO # If the INLINE_INFO tag is set to YES (the default) then a tag [inline] # is inserted in the documentation for inline members. INLINE_INFO = YES # If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen # will sort the (detailed) documentation of file and class members # alphabetically by member name. If set to NO the members will appear in # declaration order. SORT_MEMBER_DOCS = YES # If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the # brief documentation of file, namespace and class members alphabetically # by member name. If set to NO (the default) the members will appear in # declaration order. SORT_BRIEF_DOCS = NO # If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen # will sort the (brief and detailed) documentation of class members so that # constructors and destructors are listed first. If set to NO (the default) # the constructors will appear in the respective orders defined by # SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. # This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO # and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. SORT_MEMBERS_CTORS_1ST = NO # If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the # hierarchy of group names into alphabetical order. If set to NO (the default) # the group names will appear in their defined order. SORT_GROUP_NAMES = NO # If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be # sorted by fully-qualified names, including namespaces. If set to # NO (the default), the class list will be sorted only by class name, # not including the namespace part. # Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. # Note: This option applies only to the class list, not to the # alphabetical list. SORT_BY_SCOPE_NAME = NO # If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to # do proper type resolution of all parameters of a function it will reject a # match between the prototype and the implementation of a member function even # if there is only one candidate or it is obvious which candidate to choose # by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen # will still accept a match between prototype and implementation in such cases. STRICT_PROTO_MATCHING = NO # The GENERATE_TODOLIST tag can be used to enable (YES) or # disable (NO) the todo list. This list is created by putting \todo # commands in the documentation. GENERATE_TODOLIST = YES # The GENERATE_TESTLIST tag can be used to enable (YES) or # disable (NO) the test list. This list is created by putting \test # commands in the documentation. GENERATE_TESTLIST = YES # The GENERATE_BUGLIST tag can be used to enable (YES) or # disable (NO) the bug list. This list is created by putting \bug # commands in the documentation. GENERATE_BUGLIST = YES # The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or # disable (NO) the deprecated list. This list is created by putting # \deprecated commands in the documentation. GENERATE_DEPRECATEDLIST= YES # The ENABLED_SECTIONS tag can be used to enable conditional # documentation sections, marked by \if sectionname ... \endif. ENABLED_SECTIONS = # The MAX_INITIALIZER_LINES tag determines the maximum number of lines # the initial value of a variable or macro consists of for it to appear in # the documentation. If the initializer consists of more lines than specified # here it will be hidden. Use a value of 0 to hide initializers completely. # The appearance of the initializer of individual variables and macros in the # documentation can be controlled using \showinitializer or \hideinitializer # command in the documentation regardless of this setting. MAX_INITIALIZER_LINES = 30 # Set the SHOW_USED_FILES tag to NO to disable the list of files generated # at the bottom of the documentation of classes and structs. If set to YES the # list will mention the files that were used to generate the documentation. SHOW_USED_FILES = YES # If the sources in your project are distributed over multiple directories # then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy # in the documentation. The default is NO. SHOW_DIRECTORIES = NO # Set the SHOW_FILES tag to NO to disable the generation of the Files page. # This will remove the Files entry from the Quick Index and from the # Folder Tree View (if specified). The default is YES. SHOW_FILES = YES # Set the SHOW_NAMESPACES tag to NO to disable the generation of the # Namespaces page. # This will remove the Namespaces entry from the Quick Index # and from the Folder Tree View (if specified). The default is YES. SHOW_NAMESPACES = YES # The FILE_VERSION_FILTER tag can be used to specify a program or script that # doxygen should invoke to get the current version for each file (typically from # the version control system). Doxygen will invoke the program by executing (via # popen()) the command , where is the value of # the FILE_VERSION_FILTER tag, and is the name of an input file # provided by doxygen. Whatever the program writes to standard output # is used as the file version. See the manual for examples. FILE_VERSION_FILTER = # The LAYOUT_FILE tag can be used to specify a layout file which will be parsed # by doxygen. The layout file controls the global structure of the generated # output files in an output format independent way. The create the layout file # that represents doxygen's defaults, run doxygen with the -l option. # You can optionally specify a file name after the option, if omitted # DoxygenLayout.xml will be used as the name of the layout file. LAYOUT_FILE = # The CITE_BIB_FILES tag can be used to specify one or more bib files # containing the references data. This must be a list of .bib files. The # .bib extension is automatically appended if omitted. Using this command # requires the bibtex tool to be installed. See also # http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style # of the bibliography can be controlled using LATEX_BIB_STYLE. To use this # feature you need bibtex and perl available in the search path. CITE_BIB_FILES = #--------------------------------------------------------------------------- # configuration options related to warning and progress messages #--------------------------------------------------------------------------- # The QUIET tag can be used to turn on/off the messages that are generated # by doxygen. Possible values are YES and NO. If left blank NO is used. QUIET = NO # The WARNINGS tag can be used to turn on/off the warning messages that are # generated by doxygen. Possible values are YES and NO. If left blank # NO is used. WARNINGS = YES # If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings # for undocumented members. If EXTRACT_ALL is set to YES then this flag will # automatically be disabled. WARN_IF_UNDOCUMENTED = YES # If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for # potential errors in the documentation, such as not documenting some # parameters in a documented function, or documenting parameters that # don't exist or using markup commands wrongly. WARN_IF_DOC_ERROR = YES # The WARN_NO_PARAMDOC option can be enabled to get warnings for # functions that are documented, but have no documentation for their parameters # or return value. If set to NO (the default) doxygen will only warn about # wrong or incomplete parameter documentation, but not about the absence of # documentation. WARN_NO_PARAMDOC = NO # The WARN_FORMAT tag determines the format of the warning messages that # doxygen can produce. The string should contain the $file, $line, and $text # tags, which will be replaced by the file and line number from which the # warning originated and the warning text. Optionally the format may contain # $version, which will be replaced by the version of the file (if it could # be obtained via FILE_VERSION_FILTER) WARN_FORMAT = "$file:$line: $text" # The WARN_LOGFILE tag can be used to specify a file to which warning # and error messages should be written. If left blank the output is written # to stderr. WARN_LOGFILE = #--------------------------------------------------------------------------- # configuration options related to the input files #--------------------------------------------------------------------------- # The INPUT tag can be used to specify the files and/or directories that contain # documented source files. You may enter file names like "myfile.cpp" or # directories like "/usr/src/myproject". Separate the files or directories # with spaces. INPUT = "include" INPUT += "doc/addons" # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is # also the default input encoding. Doxygen uses libiconv (or the iconv built # into libc) for the transcoding. See http://www.gnu.org/software/libiconv for # the list of possible encodings. INPUT_ENCODING = UTF-8 # If the value of the INPUT tag contains directories, you can use the # FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp # and *.h) to filter out the source-files in the directories. If left # blank the following patterns are tested: # *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh # *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py # *.f90 *.f *.for *.vhd *.vhdl FILE_PATTERNS = # The RECURSIVE tag can be used to turn specify whether or not subdirectories # should be searched for input files as well. Possible values are YES and NO. # If left blank NO is used. RECURSIVE = YES # The EXCLUDE tag can be used to specify files and/or directories that should be # excluded from the INPUT source files. This way you can easily exclude a # subdirectory from a directory tree whose root is specified with the INPUT tag. # Note that relative paths are relative to the directory from which doxygen is # run. EXCLUDE = # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # directories that are symbolic links (a Unix file system feature) are excluded # from the input. EXCLUDE_SYMLINKS = NO # If the value of the INPUT tag contains directories, you can use the # EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude # certain files from those directories. Note that the wildcards are matched # against the file with absolute path, so to exclude all test directories # for example use the pattern */test/* EXCLUDE_PATTERNS = "*/implementation/*" EXCLUDE_PATTERNS += "*/modules/*" # The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names # (namespaces, classes, functions, etc.) that should be excluded from the # output. The symbol name can be a fully qualified name, a word, or if the # wildcard * is used, a substring. Examples: ANamespace, AClass, # AClass::ANamespace, ANamespace::*Test EXCLUDE_SYMBOLS = # The EXAMPLE_PATH tag can be used to specify one or more files or # directories that contain example code fragments that are included (see # the \include command). EXAMPLE_PATH = # If the value of the EXAMPLE_PATH tag contains directories, you can use the # EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp # and *.h) to filter out the source-files in the directories. If left # blank all files are included. EXAMPLE_PATTERNS = # If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be # searched for input files to be used with the \include or \dontinclude # commands irrespective of the value of the RECURSIVE tag. # Possible values are YES and NO. If left blank NO is used. EXAMPLE_RECURSIVE = NO # The IMAGE_PATH tag can be used to specify one or more files or # directories that contain image that are included in the documentation (see # the \image command). IMAGE_PATH = "doc/addons/images" # The INPUT_FILTER tag can be used to specify a program that doxygen should # invoke to filter for each input file. Doxygen will invoke the filter program # by executing (via popen()) the command , where # is the value of the INPUT_FILTER tag, and is the name of an # input file. Doxygen will then use the output that the filter program writes # to standard output. # If FILTER_PATTERNS is specified, this tag will be # ignored. INPUT_FILTER = # The FILTER_PATTERNS tag can be used to specify filters on a per file pattern # basis. # Doxygen will compare the file name with each pattern and apply the # filter if there is a match. # The filters are a list of the form: # pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further # info on how filters are used. If FILTER_PATTERNS is empty or if # non of the patterns match the file name, INPUT_FILTER is applied. FILTER_PATTERNS = # If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using # INPUT_FILTER) will be used to filter the input files when producing source # files to browse (i.e. when SOURCE_BROWSER is set to YES). FILTER_SOURCE_FILES = NO # The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file # pattern. A pattern will override the setting for FILTER_PATTERN (if any) # and it is also possible to disable source filtering for a specific pattern # using *.ext= (so without naming a filter). This option only has effect when # FILTER_SOURCE_FILES is enabled. FILTER_SOURCE_PATTERNS = #--------------------------------------------------------------------------- # configuration options related to source browsing #--------------------------------------------------------------------------- # If the SOURCE_BROWSER tag is set to YES then a list of source files will # be generated. Documented entities will be cross-referenced with these sources. # Note: To get rid of all source code in the generated output, make sure also # VERBATIM_HEADERS is set to NO. SOURCE_BROWSER = NO # Setting the INLINE_SOURCES tag to YES will include the body # of functions and classes directly in the documentation. INLINE_SOURCES = NO # Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct # doxygen to hide any special comment blocks from generated source code # fragments. Normal C and C++ comments will always remain visible. STRIP_CODE_COMMENTS = YES # If the REFERENCED_BY_RELATION tag is set to YES # then for each documented function all documented # functions referencing it will be listed. REFERENCED_BY_RELATION = NO # If the REFERENCES_RELATION tag is set to YES # then for each documented function all documented entities # called/used by that function will be listed. REFERENCES_RELATION = NO # If the REFERENCES_LINK_SOURCE tag is set to YES (the default) # and SOURCE_BROWSER tag is set to YES, then the hyperlinks from # functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will # link to the source code. # Otherwise they will link to the documentation. REFERENCES_LINK_SOURCE = YES # If the USE_HTAGS tag is set to YES then the references to source code # will point to the HTML generated by the htags(1) tool instead of doxygen # built-in source browser. The htags tool is part of GNU's global source # tagging system (see http://www.gnu.org/software/global/global.html). You # will need version 4.8.6 or higher. USE_HTAGS = NO # If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen # will generate a verbatim copy of the header file for each class for # which an include is specified. Set to NO to disable this. VERBATIM_HEADERS = YES #--------------------------------------------------------------------------- # configuration options related to the alphabetical class index #--------------------------------------------------------------------------- # If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index # of all compounds will be generated. Enable this if the project # contains a lot of classes, structs, unions or interfaces. ALPHABETICAL_INDEX = YES # If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then # the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns # in which this list will be split (can be a number in the range [1..20]) COLS_IN_ALPHA_INDEX = 5 # In case all classes in a project start with a common prefix, all # classes will be put under the same header in the alphabetical index. # The IGNORE_PREFIX tag can be used to specify one or more prefixes that # should be ignored while generating the index headers. IGNORE_PREFIX = #--------------------------------------------------------------------------- # configuration options related to the HTML output #--------------------------------------------------------------------------- # If the GENERATE_HTML tag is set to YES (the default) Doxygen will # generate HTML output. GENERATE_HTML = YES # The HTML_OUTPUT tag is used to specify where the HTML docs will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `html' will be used as the default path. HTML_OUTPUT = html # The HTML_FILE_EXTENSION tag can be used to specify the file extension for # each generated HTML page (for example: .htm,.php,.asp). If it is left blank # doxygen will generate files with .html extension. HTML_FILE_EXTENSION = .html # The HTML_HEADER tag can be used to specify a personal HTML header for # each generated HTML page. If it is left blank doxygen will generate a # standard header. Note that when using a custom header you are responsible # for the proper inclusion of any scripts and style sheets that doxygen # needs, which is dependent on the configuration options used. # It is advised to generate a default header using "doxygen -w html # header.html footer.html stylesheet.css YourConfigFile" and then modify # that header. Note that the header is subject to change so you typically # have to redo this when upgrading to a newer version of doxygen or when # changing the value of configuration settings such as GENERATE_TREEVIEW! HTML_HEADER = # The HTML_FOOTER tag can be used to specify a personal HTML footer for # each generated HTML page. If it is left blank doxygen will generate a # standard footer. HTML_FOOTER = # The HTML_STYLESHEET tag can be used to specify a user-defined cascading # style sheet that is used by each HTML page. It can be used to # fine-tune the look of the HTML output. If the tag is left blank doxygen # will generate a default style sheet. Note that doxygen will try to copy # the style sheet file to the HTML output directory, so don't put your own # style sheet in the HTML output directory as well, or it will be erased! HTML_STYLESHEET = # The HTML_EXTRA_FILES tag can be used to specify one or more extra images or # other source files which should be copied to the HTML output directory. Note # that these files will be copied to the base HTML output directory. Use the # $relpath$ marker in the HTML_HEADER and/or HTML_FOOTER files to load these # files. In the HTML_STYLESHEET file, use the file name only. Also note that # the files will be copied as-is; there are no commands or markers available. HTML_EXTRA_FILES = # The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. # Doxygen will adjust the colors in the style sheet and background images # according to this color. Hue is specified as an angle on a colorwheel, # see http://en.wikipedia.org/wiki/Hue for more information. # For instance the value 0 represents red, 60 is yellow, 120 is green, # 180 is cyan, 240 is blue, 300 purple, and 360 is red again. # The allowed range is 0 to 359. HTML_COLORSTYLE_HUE = 220 # The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of # the colors in the HTML output. For a value of 0 the output will use # grayscales only. A value of 255 will produce the most vivid colors. HTML_COLORSTYLE_SAT = 100 # The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to # the luminance component of the colors in the HTML output. Values below # 100 gradually make the output lighter, whereas values above 100 make # the output darker. The value divided by 100 is the actual gamma applied, # so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, # and 100 does not change the gamma. HTML_COLORSTYLE_GAMMA = 80 # If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML # page will contain the date and time when the page was generated. Setting # this to NO can help when comparing the output of multiple runs. HTML_TIMESTAMP = YES # If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, # files or namespaces will be aligned in HTML using tables. If set to # NO a bullet list will be used. HTML_ALIGN_MEMBERS = YES # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML # documentation will contain sections that can be hidden and shown after the # page has loaded. For this to work a browser that supports # JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox # Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari). HTML_DYNAMIC_SECTIONS = NO # If the GENERATE_DOCSET tag is set to YES, additional index files # will be generated that can be used as input for Apple's Xcode 3 # integrated development environment, introduced with OSX 10.5 (Leopard). # To create a documentation set, doxygen will generate a Makefile in the # HTML output directory. Running make will produce the docset in that # directory and running "make install" will install the docset in # ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find # it at startup. # See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html # for more information. GENERATE_DOCSET = NO # When GENERATE_DOCSET tag is set to YES, this tag determines the name of the # feed. A documentation feed provides an umbrella under which multiple # documentation sets from a single provider (such as a company or product suite) # can be grouped. DOCSET_FEEDNAME = "Doxygen generated docs" # When GENERATE_DOCSET tag is set to YES, this tag specifies a string that # should uniquely identify the documentation set bundle. This should be a # reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen # will append .docset to the name. DOCSET_BUNDLE_ID = org.doxygen.Project # When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely identify # the documentation publisher. This should be a reverse domain-name style # string, e.g. com.mycompany.MyDocSet.documentation. DOCSET_PUBLISHER_ID = org.doxygen.Publisher # The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. DOCSET_PUBLISHER_NAME = Publisher # If the GENERATE_HTMLHELP tag is set to YES, additional index files # will be generated that can be used as input for tools like the # Microsoft HTML help workshop to generate a compiled HTML help file (.chm) # of the generated HTML documentation. GENERATE_HTMLHELP = NO # If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can # be used to specify the file name of the resulting .chm file. You # can add a path in front of the file if the result should not be # written to the html output directory. CHM_FILE = # If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can # be used to specify the location (absolute path including file name) of # the HTML help compiler (hhc.exe). If non-empty doxygen will try to run # the HTML help compiler on the generated index.hhp. HHC_LOCATION = # If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag # controls if a separate .chi index file is generated (YES) or that # it should be included in the master .chm file (NO). GENERATE_CHI = NO # If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING # is used to encode HtmlHelp index (hhk), content (hhc) and project file # content. CHM_INDEX_ENCODING = # If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag # controls whether a binary table of contents is generated (YES) or a # normal table of contents (NO) in the .chm file. BINARY_TOC = NO # The TOC_EXPAND flag can be set to YES to add extra items for group members # to the contents of the HTML help documentation and to the tree view. TOC_EXPAND = NO # If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and # QHP_VIRTUAL_FOLDER are set, an additional index file will be generated # that can be used as input for Qt's qhelpgenerator to generate a # Qt Compressed Help (.qch) of the generated HTML documentation. GENERATE_QHP = NO # If the QHG_LOCATION tag is specified, the QCH_FILE tag can # be used to specify the file name of the resulting .qch file. # The path specified is relative to the HTML output folder. QCH_FILE = # The QHP_NAMESPACE tag specifies the namespace to use when generating # Qt Help Project output. For more information please see # http://doc.trolltech.com/qthelpproject.html#namespace QHP_NAMESPACE = org.doxygen.Project # The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating # Qt Help Project output. For more information please see # http://doc.trolltech.com/qthelpproject.html#virtual-folders QHP_VIRTUAL_FOLDER = doc # If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to # add. For more information please see # http://doc.trolltech.com/qthelpproject.html#custom-filters QHP_CUST_FILTER_NAME = # The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the # custom filter to add. For more information please see # # Qt Help Project / Custom Filters. QHP_CUST_FILTER_ATTRS = # The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this # project's # filter section matches. # # Qt Help Project / Filter Attributes. QHP_SECT_FILTER_ATTRS = # If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can # be used to specify the location of Qt's qhelpgenerator. # If non-empty doxygen will try to run qhelpgenerator on the generated # .qhp file. QHG_LOCATION = # If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files # will be generated, which together with the HTML files, form an Eclipse help # plugin. To install this plugin and make it available under the help contents # menu in Eclipse, the contents of the directory containing the HTML and XML # files needs to be copied into the plugins directory of eclipse. The name of # the directory within the plugins directory should be the same as # the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before # the help appears. GENERATE_ECLIPSEHELP = NO # A unique identifier for the eclipse help plugin. When installing the plugin # the directory name containing the HTML and XML files should also have # this name. ECLIPSE_DOC_ID = org.doxygen.Project # The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) # at top of each HTML page. The value NO (the default) enables the index and # the value YES disables it. Since the tabs have the same information as the # navigation tree you can set this option to NO if you already set # GENERATE_TREEVIEW to YES. DISABLE_INDEX = YES # The GENERATE_TREEVIEW tag is used to specify whether a tree-like index # structure should be generated to display hierarchical information. # If the tag value is set to YES, a side panel will be generated # containing a tree-like index structure (just like the one that # is generated for HTML Help). For this to work a browser that supports # JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). # Windows users are probably better off using the HTML help feature. # Since the tree basically has the same information as the tab index you # could consider to set DISABLE_INDEX to NO when enabling this option. GENERATE_TREEVIEW = YES # The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values # (range [0,1..20]) that doxygen will group on one line in the generated HTML # documentation. Note that a value of 0 will completely suppress the enum # values from appearing in the overview section. ENUM_VALUES_PER_LINE = 4 # By enabling USE_INLINE_TREES, doxygen will generate the Groups, Directories, # and Class Hierarchy pages using a tree view instead of an ordered list. USE_INLINE_TREES = NO # If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be # used to set the initial width (in pixels) of the frame in which the tree # is shown. TREEVIEW_WIDTH = 250 # When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open # links to external symbols imported via tag files in a separate window. EXT_LINKS_IN_WINDOW = NO # Use this tag to change the font size of Latex formulas included # as images in the HTML documentation. The default is 10. Note that # when you change the font size after a successful doxygen run you need # to manually remove any form_*.png images from the HTML output directory # to force them to be regenerated. FORMULA_FONTSIZE = 10 # Use the FORMULA_TRANPARENT tag to determine whether or not the images # generated for formulas are transparent PNGs. Transparent PNGs are # not supported properly for IE 6.0, but are supported on all modern browsers. # Note that when changing this option you need to delete any form_*.png files # in the HTML output before the changes have effect. FORMULA_TRANSPARENT = YES # Enable the USE_MATHJAX option to render LaTeX formulas using MathJax # (see http://www.mathjax.org) which uses client side Javascript for the # rendering instead of using prerendered bitmaps. Use this if you do not # have LaTeX installed or if you want to formulas look prettier in the HTML # output. When enabled you also need to install MathJax separately and # configure the path to it using the MATHJAX_RELPATH option. USE_MATHJAX = NO # When MathJax is enabled you need to specify the location relative to the # HTML output directory using the MATHJAX_RELPATH option. The destination # directory should contain the MathJax.js script. For instance, if the mathjax # directory is located at the same level as the HTML output directory, then # MATHJAX_RELPATH should be ../mathjax. The default value points to the # mathjax.org site, so you can quickly see the result without installing # MathJax, but it is strongly recommended to install a local copy of MathJax # before deployment. MATHJAX_RELPATH = http://www.mathjax.org/mathjax # The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension # names that should be enabled during MathJax rendering. MATHJAX_EXTENSIONS = # When the SEARCHENGINE tag is enabled doxygen will generate a search box # for the HTML output. The underlying search engine uses javascript # and DHTML and should work on any modern browser. Note that when using # HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets # (GENERATE_DOCSET) there is already a search function so this one should # typically be disabled. For large projects the javascript based search engine # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be # implemented using a PHP enabled web server instead of at the web client # using Javascript. Doxygen will generate the search PHP script and index # file to put on the web server. The advantage of the server # based approach is that it scales better to large projects and allows # full text search. The disadvantages are that it is more difficult to setup # and does not have live searching capabilities. SERVER_BASED_SEARCH = NO #--------------------------------------------------------------------------- # configuration options related to the LaTeX output #--------------------------------------------------------------------------- # If the GENERATE_LATEX tag is set to YES (the default) Doxygen will # generate Latex output. GENERATE_LATEX = YES # The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `latex' will be used as the default path. LATEX_OUTPUT = latex # The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be # invoked. If left blank `latex' will be used as the default command name. # Note that when enabling USE_PDFLATEX this option is only used for # generating bitmaps for formulas in the HTML output, but not in the # Makefile that is written to the output directory. LATEX_CMD_NAME = latex # The MAKEINDEX_CMD_NAME tag can be used to specify the command name to # generate index for LaTeX. If left blank `makeindex' will be used as the # default command name. MAKEINDEX_CMD_NAME = makeindex # If the COMPACT_LATEX tag is set to YES Doxygen generates more compact # LaTeX documents. This may be useful for small projects and may help to # save some trees in general. COMPACT_LATEX = NO # The PAPER_TYPE tag can be used to set the paper type that is used # by the printer. Possible values are: a4, letter, legal and # executive. If left blank a4wide will be used. PAPER_TYPE = a4 # The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX # packages that should be included in the LaTeX output. EXTRA_PACKAGES = # The LATEX_HEADER tag can be used to specify a personal LaTeX header for # the generated latex document. The header should contain everything until # the first chapter. If it is left blank doxygen will generate a # standard header. Notice: only use this tag if you know what you are doing! LATEX_HEADER = # The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for # the generated latex document. The footer should contain everything after # the last chapter. If it is left blank doxygen will generate a # standard footer. Notice: only use this tag if you know what you are doing! LATEX_FOOTER = # If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated # is prepared for conversion to pdf (using ps2pdf). The pdf file will # contain links (just like the HTML output) instead of page references # This makes the output suitable for online browsing using a pdf viewer. PDF_HYPERLINKS = YES # If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of # plain latex in the generated Makefile. Set this option to YES to get a # higher quality PDF documentation. USE_PDFLATEX = YES # If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. # command to the generated LaTeX files. This will instruct LaTeX to keep # running if errors occur, instead of asking the user for help. # This option is also used when generating formulas in HTML. LATEX_BATCHMODE = NO # If LATEX_HIDE_INDICES is set to YES then doxygen will not # include the index chapters (such as File Index, Compound Index, etc.) # in the output. LATEX_HIDE_INDICES = NO # If LATEX_SOURCE_CODE is set to YES then doxygen will include # source code with syntax highlighting in the LaTeX output. # Note that which sources are shown also depends on other settings # such as SOURCE_BROWSER. LATEX_SOURCE_CODE = NO # The LATEX_BIB_STYLE tag can be used to specify the style to use for the # bibliography, e.g. plainnat, or ieeetr. The default style is "plain". See # http://en.wikipedia.org/wiki/BibTeX for more info. LATEX_BIB_STYLE = plain #--------------------------------------------------------------------------- # configuration options related to the RTF output #--------------------------------------------------------------------------- # If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output # The RTF output is optimized for Word 97 and may not look very pretty with # other RTF readers or editors. GENERATE_RTF = NO # The RTF_OUTPUT tag is used to specify where the RTF docs will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `rtf' will be used as the default path. RTF_OUTPUT = rtf # If the COMPACT_RTF tag is set to YES Doxygen generates more compact # RTF documents. This may be useful for small projects and may help to # save some trees in general. COMPACT_RTF = NO # If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated # will contain hyperlink fields. The RTF file will # contain links (just like the HTML output) instead of page references. # This makes the output suitable for online browsing using WORD or other # programs which support those fields. # Note: wordpad (write) and others do not support links. RTF_HYPERLINKS = NO # Load style sheet definitions from file. Syntax is similar to doxygen's # config file, i.e. a series of assignments. You only have to provide # replacements, missing definitions are set to their default value. RTF_STYLESHEET_FILE = # Set optional variables used in the generation of an rtf document. # Syntax is similar to doxygen's config file. RTF_EXTENSIONS_FILE = #--------------------------------------------------------------------------- # configuration options related to the man page output #--------------------------------------------------------------------------- # If the GENERATE_MAN tag is set to YES (the default) Doxygen will # generate man pages GENERATE_MAN = NO # The MAN_OUTPUT tag is used to specify where the man pages will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `man' will be used as the default path. MAN_OUTPUT = man # The MAN_EXTENSION tag determines the extension that is added to # the generated man pages (default is the subroutine's section .3) MAN_EXTENSION = .3 # If the MAN_LINKS tag is set to YES and Doxygen generates man output, # then it will generate one additional man file for each entity # documented in the real man page(s). These additional files # only source the real man page, but without them the man command # would be unable to find the correct page. The default is NO. MAN_LINKS = NO #--------------------------------------------------------------------------- # configuration options related to the XML output #--------------------------------------------------------------------------- # If the GENERATE_XML tag is set to YES Doxygen will # generate an XML file that captures the structure of # the code including all documentation. GENERATE_XML = NO # The XML_OUTPUT tag is used to specify where the XML pages will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `xml' will be used as the default path. XML_OUTPUT = xml # The XML_SCHEMA tag can be used to specify an XML schema, # which can be used by a validating XML parser to check the # syntax of the XML files. XML_SCHEMA = # The XML_DTD tag can be used to specify an XML DTD, # which can be used by a validating XML parser to check the # syntax of the XML files. XML_DTD = # If the XML_PROGRAMLISTING tag is set to YES Doxygen will # dump the program listings (including syntax highlighting # and cross-referencing information) to the XML output. Note that # enabling this will significantly increase the size of the XML output. XML_PROGRAMLISTING = YES #--------------------------------------------------------------------------- # configuration options for the AutoGen Definitions output #--------------------------------------------------------------------------- # If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will # generate an AutoGen Definitions (see autogen.sf.net) file # that captures the structure of the code including all # documentation. Note that this feature is still experimental # and incomplete at the moment. GENERATE_AUTOGEN_DEF = NO #--------------------------------------------------------------------------- # configuration options related to the Perl module output #--------------------------------------------------------------------------- # If the GENERATE_PERLMOD tag is set to YES Doxygen will # generate a Perl module file that captures the structure of # the code including all documentation. Note that this # feature is still experimental and incomplete at the # moment. GENERATE_PERLMOD = NO # If the PERLMOD_LATEX tag is set to YES Doxygen will generate # the necessary Makefile rules, Perl scripts and LaTeX code to be able # to generate PDF and DVI output from the Perl module output. PERLMOD_LATEX = NO # If the PERLMOD_PRETTY tag is set to YES the Perl module output will be # nicely formatted so it can be parsed by a human reader. # This is useful # if you want to understand what is going on. # On the other hand, if this # tag is set to NO the size of the Perl module output will be much smaller # and Perl will parse it just the same. PERLMOD_PRETTY = YES # The names of the make variables in the generated doxyrules.make file # are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. # This is useful so different doxyrules.make files included by the same # Makefile don't overwrite each other's variables. PERLMOD_MAKEVAR_PREFIX = #--------------------------------------------------------------------------- # Configuration options related to the preprocessor #--------------------------------------------------------------------------- # If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will # evaluate all C-preprocessor directives found in the sources and include # files. ENABLE_PREPROCESSING = YES # If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro # names in the source code. If set to NO (the default) only conditional # compilation will be performed. Macro expansion can be done in a controlled # way by setting EXPAND_ONLY_PREDEF to YES. MACRO_EXPANSION = NO # If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES # then the macro expansion is limited to the macros specified with the # PREDEFINED and EXPAND_AS_DEFINED tags. EXPAND_ONLY_PREDEF = NO # If the SEARCH_INCLUDES tag is set to YES (the default) the includes files # pointed to by INCLUDE_PATH will be searched when a #include is found. SEARCH_INCLUDES = YES # The INCLUDE_PATH tag can be used to specify one or more directories that # contain include files that are not input files but should be processed by # the preprocessor. INCLUDE_PATH = # You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard # patterns (like *.h and *.hpp) to filter out the header-files in the # directories. If left blank, the patterns specified with FILE_PATTERNS will # be used. INCLUDE_FILE_PATTERNS = # The PREDEFINED tag can be used to specify one or more macro names that # are defined before the preprocessor is started (similar to the -D option of # gcc). The argument of the tag is a list of macros of the form: name # or name=definition (no spaces). If the definition and the = are # omitted =1 is assumed. To prevent a macro definition from being # undefined via #undef or recursively expanded use the := operator # instead of the = operator. PREDEFINED = # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then # this tag can be used to specify a list of macro names that should be expanded. # The macro definition that is found in the sources will be used. # Use the PREDEFINED tag if you want to use a different macro definition that # overrules the definition found in the source code. EXPAND_AS_DEFINED = # If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then # doxygen's preprocessor will remove all references to function-like macros # that are alone on a line, have an all uppercase name, and do not end with a # semicolon, because these will confuse the parser if not removed. SKIP_FUNCTION_MACROS = YES #--------------------------------------------------------------------------- # Configuration::additions related to external references #--------------------------------------------------------------------------- # The TAGFILES option can be used to specify one or more tagfiles. # Optionally an initial location of the external documentation # can be added for each tagfile. The format of a tag file without # this location is as follows: # # TAGFILES = file1 file2 ... # Adding location for the tag files is done as follows: # # TAGFILES = file1=loc1 "file2 = loc2" ... # where "loc1" and "loc2" can be relative or absolute paths or # URLs. If a location is present for each tag, the installdox tool # does not have to be run to correct the links. # Note that each tag file must have a unique name # (where the name does NOT include the path) # If a tag file is not located in the directory in which doxygen # is run, you must also specify the path to the tagfile here. TAGFILES = # When a file name is specified after GENERATE_TAGFILE, doxygen will create # a tag file that is based on the input files it reads. GENERATE_TAGFILE = # If the ALLEXTERNALS tag is set to YES all external classes will be listed # in the class index. If set to NO only the inherited external classes # will be listed. ALLEXTERNALS = NO # If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed # in the modules index. If set to NO, only the current project's groups will # be listed. EXTERNAL_GROUPS = YES # The PERL_PATH should be the absolute path and name of the perl script # interpreter (i.e. the result of `which perl'). PERL_PATH = /usr/bin/perl #--------------------------------------------------------------------------- # Configuration options related to the dot tool #--------------------------------------------------------------------------- # If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will # generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base # or super classes. Setting the tag to NO turns the diagrams off. Note that # this option also works with HAVE_DOT disabled, but it is recommended to # install and use dot, since it yields more powerful graphs. CLASS_DIAGRAMS = YES # You can define message sequence charts within doxygen comments using the \msc # command. Doxygen will then run the mscgen tool (see # http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the # documentation. The MSCGEN_PATH tag allows you to specify the directory where # the mscgen tool resides. If left empty the tool is assumed to be found in the # default search path. MSCGEN_PATH = # If set to YES, the inheritance and collaboration graphs will hide # inheritance and usage relations if the target is undocumented # or is not a class. HIDE_UNDOC_RELATIONS = YES # If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is # available from the path. This tool is part of Graphviz, a graph visualization # toolkit from AT&T and Lucent Bell Labs. The other options in this section # have no effect if this option is set to NO (the default) HAVE_DOT = NO # The DOT_NUM_THREADS specifies the number of dot invocations doxygen is # allowed to run in parallel. When set to 0 (the default) doxygen will # base this on the number of processors available in the system. You can set it # explicitly to a value larger than 0 to get control over the balance # between CPU load and processing speed. DOT_NUM_THREADS = 0 # By default doxygen will use the Helvetica font for all dot files that # doxygen generates. When you want a differently looking font you can specify # the font name using DOT_FONTNAME. You need to make sure dot is able to find # the font, which can be done by putting it in a standard location or by setting # the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the # directory containing the font. DOT_FONTNAME = Helvetica # The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. # The default size is 10pt. DOT_FONTSIZE = 10 # By default doxygen will tell dot to use the Helvetica font. # If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to # set the path where dot can find it. DOT_FONTPATH = # If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen # will generate a graph for each documented class showing the direct and # indirect inheritance relations. Setting this tag to YES will force the # CLASS_DIAGRAMS tag to NO. CLASS_GRAPH = YES # If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen # will generate a graph for each documented class showing the direct and # indirect implementation dependencies (inheritance, containment, and # class references variables) of the class with other documented classes. COLLABORATION_GRAPH = YES # If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen # will generate a graph for groups, showing the direct groups dependencies GROUP_GRAPHS = YES # If the UML_LOOK tag is set to YES doxygen will generate inheritance and # collaboration diagrams in a style similar to the OMG's Unified Modeling # Language. UML_LOOK = NO # If set to YES, the inheritance and collaboration graphs will show the # relations between templates and their instances. TEMPLATE_RELATIONS = NO # If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT # tags are set to YES then doxygen will generate a graph for each documented # file showing the direct and indirect include dependencies of the file with # other documented files. INCLUDE_GRAPH = YES # If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and # HAVE_DOT tags are set to YES then doxygen will generate a graph for each # documented header file showing the documented files that directly or # indirectly include this file. INCLUDED_BY_GRAPH = YES # If the CALL_GRAPH and HAVE_DOT options are set to YES then # doxygen will generate a call dependency graph for every global function # or class method. Note that enabling this option will significantly increase # the time of a run. So in most cases it will be better to enable call graphs # for selected functions only using the \callgraph command. CALL_GRAPH = NO # If the CALLER_GRAPH and HAVE_DOT tags are set to YES then # doxygen will generate a caller dependency graph for every global function # or class method. Note that enabling this option will significantly increase # the time of a run. So in most cases it will be better to enable caller # graphs for selected functions only using the \callergraph command. CALLER_GRAPH = NO # If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen # will generate a graphical hierarchy of all classes instead of a textual one. GRAPHICAL_HIERARCHY = YES # If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES # then doxygen will show the dependencies a directory has on other directories # in a graphical way. The dependency relations are determined by the #include # relations between the files in the directories. DIRECTORY_GRAPH = YES # The DOT_IMAGE_FORMAT tag can be used to set the image format of the images # generated by dot. Possible values are svg, png, jpg, or gif. # If left blank png will be used. If you choose svg you need to set # HTML_FILE_EXTENSION to xhtml in order to make the SVG files # visible in IE 9+ (other browsers do not have this requirement). DOT_IMAGE_FORMAT = png # If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to # enable generation of interactive SVG images that allow zooming and panning. # Note that this requires a modern browser other than Internet Explorer. # Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you # need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files # visible. Older versions of IE do not have SVG support. INTERACTIVE_SVG = NO # The tag DOT_PATH can be used to specify the path where the dot tool can be # found. If left blank, it is assumed the dot tool can be found in the path. DOT_PATH = # The DOTFILE_DIRS tag can be used to specify one or more directories that # contain dot files that are included in the documentation (see the # \dotfile command). DOTFILE_DIRS = # The MSCFILE_DIRS tag can be used to specify one or more directories that # contain msc files that are included in the documentation (see the # \mscfile command). MSCFILE_DIRS = # The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of # nodes that will be shown in the graph. If the number of nodes in a graph # becomes larger than this value, doxygen will truncate the graph, which is # visualized by representing a node as a red box. Note that doxygen if the # number of direct children of the root node in a graph is already larger than # DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note # that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. DOT_GRAPH_MAX_NODES = 50 # The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the # graphs generated by dot. A depth value of 3 means that only nodes reachable # from the root by following a path via at most 3 edges will be shown. Nodes # that lay further from the root node will be omitted. Note that setting this # option to 1 or 2 may greatly reduce the computation time needed for large # code bases. Also note that the size of a graph can be further restricted by # DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. MAX_DOT_GRAPH_DEPTH = 0 # Set the DOT_TRANSPARENT tag to YES to generate images with a transparent # background. This is disabled by default, because dot on Windows does not # seem to support this out of the box. Warning: Depending on the platform used, # enabling this option may lead to badly anti-aliased labels on the edges of # a graph (i.e. they become hard to read). DOT_TRANSPARENT = NO # Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output # files in one run (i.e. multiple -o and -T options on the command line). This # makes dot run faster, but since only newer versions of dot (>1.8.10) # support this, this feature is disabled by default. DOT_MULTI_TARGETS = YES # If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will # generate a legend page explaining the meaning of the various boxes and # arrows in the dot generated graphs. GENERATE_LEGEND = YES # If the DOT_CLEANUP tag is set to YES (the default) Doxygen will # remove the intermediate dot files that are used to generate # the various graphs. DOT_CLEANUP = YES opengv/python/0000775016516101651610000000000013635643413012333 5ustar dimadimaopengv/python/types.hpp0000664016516101651610000000157013635643413014213 0ustar dimadima#ifndef __TYPES_H__ #define __TYPES_H__ #include #include #include #include namespace pyopengv { namespace py = pybind11; typedef py::array_t pyarray_d; template py::array_t py_array_from_data(const T *data, size_t shape0) { py::array_t res({shape0}); std::copy(data, data + shape0, res.mutable_data()); return res; } template py::array_t py_array_from_data(const T *data, size_t shape0, size_t shape1) { py::array_t res({shape0, shape1}); std::copy(data, data + shape0 * shape1, res.mutable_data()); return res; } template py::array_t py_array_from_vector(const std::vector &v) { const T *data = v.size() ? &v[0] : NULL; return py_array_from_data(data, v.size()); } } #endif // __TYPES_H__ opengv/python/CMakeLists.txt0000664016516101651610000000123513635643413015074 0ustar dimadima add_subdirectory(pybind11) include_directories(${PYTHON_INCLUDE_DIRS}) pybind11_add_module(pyopengv pyopengv.cpp) target_link_libraries(pyopengv PRIVATE opengv) # Find where to install python libs. execute_process(COMMAND ${PYTHON_EXECUTABLE} -c "import distutils.sysconfig; print('/'.join(distutils.sysconfig.get_python_lib().split('/')[-3:]))" OUTPUT_VARIABLE PYTHON_SITE_PACKAGES OUTPUT_STRIP_TRAILING_WHITESPACE) set(PYTHON_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${PYTHON_SITE_PACKAGES}" CACHE PATH "Path where to install pyopengv") install(TARGETS pyopengv DESTINATION "${PYTHON_INSTALL_DIR}") message(python executable ${PYTHON_EXECUTABLE})opengv/python/pybind11/0000775016516101651610000000000013635643413013762 5ustar dimadimaopengv/python/tests.py0000664016516101651610000001757113635643413014062 0ustar dimadimaimport pyopengv import numpy as np def normalized(x): return x / np.linalg.norm(x) def generateRandomPoint(maximumDepth, minimumDepth): cleanPoint = np.random.uniform(-1.0, 1.0, 3) direction = normalized(cleanPoint) return (maximumDepth - minimumDepth) * cleanPoint + minimumDepth * direction def generateRandomTranslation(maximumParallax): return np.random.uniform(-maximumParallax, maximumParallax, 3) def generateRandomRotation(maxAngle): rpy = np.random.uniform(-maxAngle, maxAngle, 3) R1 = np.array([[1.0, 0.0, 0.0], [0.0, np.cos(rpy[0]), -np.sin(rpy[0])], [0.0, np.sin(rpy[0]), np.cos(rpy[0])]]) R2 = np.array([[np.cos(rpy[1]), 0.0, np.sin(rpy[1])], [0.0, 1.0, 0.0], [-np.sin(rpy[1]), 0.0, np.cos(rpy[1])]]) R3 = np.array([[np.cos(rpy[2]), -np.sin(rpy[2]), 0.0], [np.sin(rpy[2]), np.cos(rpy[2]), 0.0], [0.0, 0.0, 1.0]]) return R3.dot(R2.dot(R1)) def addNoise(noiseLevel, cleanPoint): noisyPoint = cleanPoint + np.random.uniform(-noiseLevel, noiseLevel, 3) return normalized(noisyPoint) def extractRelativePose(position1, position2, rotation1, rotation2): relativeRotation = rotation1.T.dot(rotation2) relativePosition = rotation1.T.dot(position2 - position1) return relativePosition, relativeRotation def essentialMatrix(position, rotation): # E transforms vectors from vp 2 to 1: x_1^T * E * x_2 = 0 # and E = (t)_skew*R t_skew = np.zeros((3, 3)) t_skew[0, 1] = -position[2] t_skew[0, 2] = position[1] t_skew[1, 0] = position[2] t_skew[1, 2] = -position[0] t_skew[2, 0] = -position[1] t_skew[2, 1] = position[0] E = t_skew.dot(rotation) return normalized(E) def getPerturbedPose(position, rotation, amplitude): dp = generateRandomTranslation(amplitude) dR = generateRandomRotation(amplitude) return position + dp, rotation.dot(dR) def proportional(x, y, tol=1e-2): xn = normalized(x) yn = normalized(y) return (np.allclose(xn, yn, rtol=1e20, atol=tol) or np.allclose(xn, -yn, rtol=1e20, atol=tol)) def matrix_in_list(a, l): for b in l: if proportional(a, b): return True return False def same_transformation(position, rotation, transformation): R = transformation[:, :3] t = transformation[:, 3] return proportional(position, t) and proportional(rotation, R) class RelativePoseDataset: def __init__(self, num_points, noise, outlier_fraction, rotation_only=False): # generate a random pose for viewpoint 1 position1 = np.zeros(3) rotation1 = np.eye(3) # generate a random pose for viewpoint 2 if rotation_only: position2 = np.zeros(3) else: position2 = generateRandomTranslation(2.0) rotation2 = generateRandomRotation(0.5) # derive correspondences based on random point-cloud self.generateCorrespondences( position1, rotation1, position2, rotation2, num_points, noise, outlier_fraction) # Extract the relative pose self.position, self.rotation = extractRelativePose( position1, position2, rotation1, rotation2) if not rotation_only: self.essential = essentialMatrix(self.position, self.rotation) def generateCorrespondences(self, position1, rotation1, position2, rotation2, num_points, noise, outlier_fraction): min_depth = 4 max_depth = 8 # initialize point-cloud self.points = np.empty((num_points, 3)) for i in range(num_points): self.points[i] = generateRandomPoint(max_depth, min_depth) self.bearing_vectors1 = np.empty((num_points, 3)) self.bearing_vectors2 = np.empty((num_points, 3)) for i in range(num_points): # get the point in viewpoint 1 body_point1 = rotation1.T.dot(self.points[i] - position1) # get the point in viewpoint 2 body_point2 = rotation2.T.dot(self.points[i] - position2) self.bearing_vectors1[i] = normalized(body_point1) self.bearing_vectors2[i] = normalized(body_point2) # add noise if noise > 0.0: self.bearing_vectors1[i] = addNoise(noise, self.bearing_vectors1[i]) self.bearing_vectors2[i] = addNoise(noise, self.bearing_vectors2[i]) # add outliers num_outliers = int(outlier_fraction * num_points) for i in range(num_outliers): # create random point p = generateRandomPoint(max_depth, min_depth) # project this point into viewpoint 2 body_point = rotation2.T.dot(p - position2) # normalize the bearing vector self.bearing_vectors2[i] = normalized(body_point) def test_relative_pose(): print("Testing relative pose") d = RelativePoseDataset(10, 0.0, 0.0) # running experiments twopt_translation = pyopengv.relative_pose_twopt( d.bearing_vectors1, d.bearing_vectors2, d.rotation) fivept_nister_essentials = pyopengv.relative_pose_fivept_nister( d.bearing_vectors1, d.bearing_vectors2) fivept_kneip_rotations = pyopengv.relative_pose_fivept_kneip( d.bearing_vectors1, d.bearing_vectors2) sevenpt_essentials = pyopengv.relative_pose_sevenpt(d.bearing_vectors1, d.bearing_vectors2) eightpt_essential = pyopengv.relative_pose_eightpt(d.bearing_vectors1, d.bearing_vectors2) t_perturbed, R_perturbed = getPerturbedPose(d.position, d.rotation, 0.01) eigensolver_rotation = pyopengv.relative_pose_eigensolver( d.bearing_vectors1, d.bearing_vectors2, R_perturbed) t_perturbed, R_perturbed = getPerturbedPose(d.position, d.rotation, 0.1) nonlinear_transformation = pyopengv.relative_pose_optimize_nonlinear( d.bearing_vectors1, d.bearing_vectors2, t_perturbed, R_perturbed) assert proportional(d.position, twopt_translation) assert matrix_in_list(d.essential, fivept_nister_essentials) assert matrix_in_list(d.rotation, fivept_kneip_rotations) assert matrix_in_list(d.essential, sevenpt_essentials) assert proportional(d.essential, eightpt_essential) assert proportional(d.rotation, eigensolver_rotation) assert same_transformation(d.position, d.rotation, nonlinear_transformation) print("Done testing relative pose") def test_relative_pose_ransac(): print("Testing relative pose ransac") d = RelativePoseDataset(100, 0.0, 0.3) ransac_transformation = pyopengv.relative_pose_ransac( d.bearing_vectors1, d.bearing_vectors2, "NISTER", 0.01, 1000) assert same_transformation(d.position, d.rotation, ransac_transformation) print("Done testing relative pose ransac") def test_relative_pose_ransac_rotation_only(): print("Testing relative pose ransac rotation only") d = RelativePoseDataset(100, 0.0, 0.3, rotation_only=True) ransac_rotation = pyopengv.relative_pose_ransac_rotation_only( d.bearing_vectors1, d.bearing_vectors2, 0.01, 1000) assert proportional(d.rotation, ransac_rotation) print("Done testing relative pose ransac rotation only") def test_triangulation(): print("Testing triangulation") d = RelativePoseDataset(10, 0.0, 0.0) points1 = pyopengv.triangulation_triangulate( d.bearing_vectors1, d.bearing_vectors2, d.position, d.rotation) assert np.allclose(d.points, points1) points2 = pyopengv.triangulation_triangulate2( d.bearing_vectors1, d.bearing_vectors2, d.position, d.rotation) assert np.allclose(d.points, points2) print("Done testing triangulation") if __name__ == "__main__": test_relative_pose() test_relative_pose_ransac() test_relative_pose_ransac_rotation_only() test_triangulation() opengv/python/pyopengv.cpp0000664016516101651610000005042713635643413014716 0ustar dimadima#include #include #include #include #include #include #include #include #include #include #include #include #include "types.hpp" namespace pyopengv { opengv::bearingVector_t bearingVectorFromArray( const pyarray_d &array, size_t index ) { opengv::bearingVector_t v; v[0] = *array.data(index, 0); v[1] = *array.data(index, 1); v[2] = *array.data(index, 2); return v; } opengv::point_t pointFromArray( const pyarray_d &array, size_t index ) { opengv::point_t p; p[0] = *array.data(index, 0); p[1] = *array.data(index, 1); p[2] = *array.data(index, 2); return p; } py::object arrayFromPoints( const opengv::points_t &points ) { std::vector data(points.size() * 3); for (size_t i = 0; i < points.size(); ++i) { data[3 * i + 0] = points[i][0]; data[3 * i + 1] = points[i][1]; data[3 * i + 2] = points[i][2]; } return py_array_from_data(&data[0], points.size(), 3); } py::object arrayFromTranslation( const opengv::translation_t &t ) { return py_array_from_data(t.data(), 3); } py::object arrayFromRotation( const opengv::rotation_t &R ) { Eigen::Matrix R_row_major = R; return py_array_from_data(R_row_major.data(), 3, 3); } py::list listFromRotations( const opengv::rotations_t &Rs ) { py::list retn; for (size_t i = 0; i < Rs.size(); ++i) { retn.append(arrayFromRotation(Rs[i])); } return retn; } py::object arrayFromEssential( const opengv::essential_t &E ) { Eigen::Matrix E_row_major = E; return py_array_from_data(E_row_major.data(), 3, 3); } py::list listFromEssentials( const opengv::essentials_t &Es ) { py::list retn; for (size_t i = 0; i < Es.size(); ++i) { retn.append(arrayFromEssential(Es[i])); } return retn; } py::object arrayFromTransformation( const opengv::transformation_t &t ) { Eigen::Matrix t_row_major = t; return py_array_from_data(t_row_major.data(), 3, 4); } py::list listFromTransformations( const opengv::transformations_t &t ) { py::list retn; for (size_t i = 0; i < t.size(); ++i) { retn.append(arrayFromTransformation(t[i])); } return retn; } std::vector getNindices( int n ) { std::vector indices; for(int i = 0; i < n; i++) indices.push_back(i); return indices; } namespace absolute_pose { class CentralAbsoluteAdapter : public opengv::absolute_pose::AbsoluteAdapterBase { protected: using AbsoluteAdapterBase::_t; using AbsoluteAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW CentralAbsoluteAdapter( pyarray_d &bearingVectors, pyarray_d &points ) : _bearingVectors(bearingVectors) , _points(points) {} CentralAbsoluteAdapter( pyarray_d &bearingVectors, pyarray_d &points, pyarray_d &R ) : _bearingVectors(bearingVectors) , _points(points) { for (int i = 0; i < 3; ++i) { for (int j = 0; j < 3; ++j) { _R(i, j) = *R.data(i, j); } } } CentralAbsoluteAdapter( pyarray_d &bearingVectors, pyarray_d &points, pyarray_d &t, pyarray_d &R ) : _bearingVectors(bearingVectors) , _points(points) { for (int i = 0; i < 3; ++i) { _t(i) = *t.data(i); } for (int i = 0; i < 3; ++i) { for (int j = 0; j < 3; ++j) { _R(i, j) = *R.data(i, j); } } } virtual ~CentralAbsoluteAdapter() {} //Access of correspondences virtual opengv::bearingVector_t getBearingVector( size_t index ) const { return bearingVectorFromArray(_bearingVectors, index); } virtual double getWeight( size_t index ) const { return 1.0; } virtual opengv::translation_t getCamOffset( size_t index ) const { return Eigen::Vector3d::Zero(); } virtual opengv::rotation_t getCamRotation( size_t index ) const { return opengv::rotation_t::Identity(); } virtual opengv::point_t getPoint( size_t index ) const { return pointFromArray(_points, index); } virtual size_t getNumberCorrespondences() const { return _bearingVectors.shape(0); } protected: pyarray_d _bearingVectors; pyarray_d _points; }; py::object p2p( pyarray_d &v, pyarray_d &p, pyarray_d &R ) { CentralAbsoluteAdapter adapter(v, p, R); return arrayFromTranslation( opengv::absolute_pose::p2p(adapter, 0, 1)); } py::object p3p_kneip( pyarray_d &v, pyarray_d &p ) { CentralAbsoluteAdapter adapter(v, p); return listFromTransformations( opengv::absolute_pose::p3p_kneip(adapter, 0, 1, 2)); } py::object p3p_gao( pyarray_d &v, pyarray_d &p ) { CentralAbsoluteAdapter adapter(v, p); return listFromTransformations( opengv::absolute_pose::p3p_gao(adapter, 0, 1, 2)); } py::object gp3p( pyarray_d &v, pyarray_d &p ) { CentralAbsoluteAdapter adapter(v, p); return listFromTransformations( opengv::absolute_pose::gp3p(adapter, 0, 1, 2)); } py::object epnp( pyarray_d &v, pyarray_d &p ) { CentralAbsoluteAdapter adapter(v, p); return arrayFromTransformation( opengv::absolute_pose::epnp(adapter)); } py::object gpnp( pyarray_d &v, pyarray_d &p ) { CentralAbsoluteAdapter adapter(v, p); return arrayFromTransformation( opengv::absolute_pose::gpnp(adapter)); } py::object upnp( pyarray_d &v, pyarray_d &p ) { CentralAbsoluteAdapter adapter(v, p); return listFromTransformations( opengv::absolute_pose::upnp(adapter)); } py::object optimize_nonlinear( pyarray_d &v, pyarray_d &p, pyarray_d &t, pyarray_d &R ) { CentralAbsoluteAdapter adapter(v, p, t, R); return arrayFromTransformation( opengv::absolute_pose::optimize_nonlinear(adapter)); } py::object ransac( pyarray_d &v, pyarray_d &p, std::string algo_name, double threshold, int max_iterations, double probability ) { using namespace opengv::sac_problems::absolute_pose; CentralAbsoluteAdapter adapter(v, p); // Create a ransac problem AbsolutePoseSacProblem::algorithm_t algorithm = AbsolutePoseSacProblem::KNEIP; if (algo_name == "TWOPT") algorithm = AbsolutePoseSacProblem::TWOPT; else if (algo_name == "KNEIP") algorithm = AbsolutePoseSacProblem::KNEIP; else if (algo_name == "GAO") algorithm = AbsolutePoseSacProblem::GAO; else if (algo_name == "EPNP") algorithm = AbsolutePoseSacProblem::EPNP; else if (algo_name == "GP3P") algorithm = AbsolutePoseSacProblem::GP3P; std::shared_ptr absposeproblem_ptr( new AbsolutePoseSacProblem(adapter, algorithm)); // Create a ransac solver for the problem opengv::sac::Ransac ransac; ransac.sac_model_ = absposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = max_iterations; ransac.probability_ = probability; // Solve ransac.computeModel(); return arrayFromTransformation(ransac.model_coefficients_); } py::object lmeds( pyarray_d &v, pyarray_d &p, std::string algo_name, double threshold, int max_iterations, double probability ) { using namespace opengv::sac_problems::absolute_pose; CentralAbsoluteAdapter adapter(v, p); // Create a lmeds problem AbsolutePoseSacProblem::algorithm_t algorithm = AbsolutePoseSacProblem::KNEIP; if (algo_name == "TWOPT") algorithm = AbsolutePoseSacProblem::TWOPT; else if (algo_name == "KNEIP") algorithm = AbsolutePoseSacProblem::KNEIP; else if (algo_name == "GAO") algorithm = AbsolutePoseSacProblem::GAO; else if (algo_name == "EPNP") algorithm = AbsolutePoseSacProblem::EPNP; else if (algo_name == "GP3P") algorithm = AbsolutePoseSacProblem::GP3P; std::shared_ptr absposeproblem_ptr( new AbsolutePoseSacProblem(adapter, algorithm)); // Create a ransac solver for the problem opengv::sac::Lmeds lmeds; lmeds.sac_model_ = absposeproblem_ptr; lmeds.threshold_ = threshold; lmeds.max_iterations_ = max_iterations; lmeds.probability_ = probability; // Solve lmeds.computeModel(); return arrayFromTransformation(lmeds.model_coefficients_); } } // namespace absolute_pose namespace relative_pose { class CentralRelativeAdapter : public opengv::relative_pose::RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW CentralRelativeAdapter( pyarray_d &bearingVectors1, pyarray_d &bearingVectors2 ) : _bearingVectors1(bearingVectors1) , _bearingVectors2(bearingVectors2) {} CentralRelativeAdapter( pyarray_d &bearingVectors1, pyarray_d &bearingVectors2, pyarray_d &R12 ) : _bearingVectors1(bearingVectors1) , _bearingVectors2(bearingVectors2) { for (int i = 0; i < 3; ++i) { for (int j = 0; j < 3; ++j) { _R12(i, j) = *R12.data(i, j); } } } CentralRelativeAdapter( pyarray_d &bearingVectors1, pyarray_d &bearingVectors2, pyarray_d &t12, pyarray_d &R12 ) : _bearingVectors1(bearingVectors1) , _bearingVectors2(bearingVectors2) { for (int i = 0; i < 3; ++i) { _t12(i) = *t12.data(i); } for (int i = 0; i < 3; ++i) { for (int j = 0; j < 3; ++j) { _R12(i, j) = *R12.data(i, j); } } } virtual ~CentralRelativeAdapter() {} virtual opengv::bearingVector_t getBearingVector1( size_t index ) const { return bearingVectorFromArray(_bearingVectors1, index); } virtual opengv::bearingVector_t getBearingVector2( size_t index ) const { return bearingVectorFromArray(_bearingVectors2, index); } virtual double getWeight( size_t index ) const { return 1.0; } virtual opengv::translation_t getCamOffset1( size_t index ) const { return Eigen::Vector3d::Zero(); } virtual opengv::rotation_t getCamRotation1( size_t index ) const { return opengv::rotation_t::Identity(); } virtual opengv::translation_t getCamOffset2( size_t index ) const { return Eigen::Vector3d::Zero(); } virtual opengv::rotation_t getCamRotation2( size_t index ) const { return opengv::rotation_t::Identity(); } virtual size_t getNumberCorrespondences() const { return _bearingVectors1.shape(0); } protected: pyarray_d _bearingVectors1; pyarray_d _bearingVectors2; }; py::object twopt( pyarray_d &b1, pyarray_d &b2, pyarray_d &R ) { CentralRelativeAdapter adapter(b1, b2, R); return arrayFromTranslation( opengv::relative_pose::twopt(adapter, true, 0, 1)); } py::object twopt_rotationOnly( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return arrayFromRotation( opengv::relative_pose::twopt_rotationOnly(adapter, 0, 1)); } py::object rotationOnly( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return arrayFromRotation( opengv::relative_pose::rotationOnly(adapter)); } py::object fivept_nister( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return listFromEssentials( opengv::relative_pose::fivept_nister(adapter)); } py::object fivept_kneip( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return listFromRotations( opengv::relative_pose::fivept_kneip(adapter, getNindices(5))); } py::object sevenpt( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return listFromEssentials( opengv::relative_pose::sevenpt(adapter)); } py::object eightpt( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return arrayFromEssential( opengv::relative_pose::eightpt(adapter)); } py::object eigensolver( pyarray_d &b1, pyarray_d &b2, pyarray_d &R ) { CentralRelativeAdapter adapter(b1, b2, R); return arrayFromRotation( opengv::relative_pose::eigensolver(adapter)); } py::object sixpt( pyarray_d &b1, pyarray_d &b2 ) { CentralRelativeAdapter adapter(b1, b2); return listFromRotations( opengv::relative_pose::sixpt(adapter)); } py::object optimize_nonlinear( pyarray_d &b1, pyarray_d &b2, pyarray_d &t12, pyarray_d &R12 ) { CentralRelativeAdapter adapter(b1, b2, t12, R12); return arrayFromTransformation( opengv::relative_pose::optimize_nonlinear(adapter)); } py::object ransac( pyarray_d &b1, pyarray_d &b2, std::string algo_name, double threshold, int max_iterations, double probability ) { using namespace opengv::sac_problems::relative_pose; CentralRelativeAdapter adapter(b1, b2); // Create a ransac problem CentralRelativePoseSacProblem::algorithm_t algorithm = CentralRelativePoseSacProblem::NISTER; if (algo_name == "STEWENIUS") algorithm = CentralRelativePoseSacProblem::STEWENIUS; else if (algo_name == "NISTER") algorithm = CentralRelativePoseSacProblem::NISTER; else if (algo_name == "SEVENPT") algorithm = CentralRelativePoseSacProblem::SEVENPT; else if (algo_name == "EIGHTPT") algorithm = CentralRelativePoseSacProblem::EIGHTPT; std::shared_ptr relposeproblem_ptr( new CentralRelativePoseSacProblem(adapter, algorithm)); // Create a ransac solver for the problem opengv::sac::Ransac ransac; ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = max_iterations; ransac.probability_ = probability; // Solve ransac.computeModel(); return arrayFromTransformation(ransac.model_coefficients_); } py::object lmeds( pyarray_d &b1, pyarray_d &b2, std::string algo_name, double threshold, int max_iterations, double probability ) { using namespace opengv::sac_problems::relative_pose; CentralRelativeAdapter adapter(b1, b2); // Create a lmeds problem CentralRelativePoseSacProblem::algorithm_t algorithm = CentralRelativePoseSacProblem::NISTER; if (algo_name == "STEWENIUS") algorithm = CentralRelativePoseSacProblem::STEWENIUS; else if (algo_name == "NISTER") algorithm = CentralRelativePoseSacProblem::NISTER; else if (algo_name == "SEVENPT") algorithm = CentralRelativePoseSacProblem::SEVENPT; else if (algo_name == "EIGHTPT") algorithm = CentralRelativePoseSacProblem::EIGHTPT; std::shared_ptr relposeproblem_ptr( new CentralRelativePoseSacProblem(adapter, algorithm)); // Create a lmeds solver for the problem opengv::sac::Lmeds lmeds; lmeds.sac_model_ = relposeproblem_ptr; lmeds.threshold_ = threshold; lmeds.max_iterations_ = max_iterations; lmeds.probability_ = probability; // Solve lmeds.computeModel(); return arrayFromTransformation(lmeds.model_coefficients_); } py::object ransac_rotationOnly( pyarray_d &b1, pyarray_d &b2, double threshold, int max_iterations, double probability ) { using namespace opengv::sac_problems::relative_pose; CentralRelativeAdapter adapter(b1, b2); std::shared_ptr relposeproblem_ptr( new RotationOnlySacProblem(adapter)); // Create a ransac solver for the problem opengv::sac::Ransac ransac; ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = max_iterations; ransac.probability_ = probability; // Solve ransac.computeModel(); return arrayFromRotation(ransac.model_coefficients_); } py::object lmeds_rotationOnly( pyarray_d &b1, pyarray_d &b2, double threshold, int max_iterations, double probability ) { using namespace opengv::sac_problems::relative_pose; CentralRelativeAdapter adapter(b1, b2); std::shared_ptr relposeproblem_ptr( new RotationOnlySacProblem(adapter)); // Create a lmeds solver for the problem opengv::sac::Lmeds lmeds; lmeds.sac_model_ = relposeproblem_ptr; lmeds.threshold_ = threshold; lmeds.max_iterations_ = max_iterations; lmeds.probability_ = probability; // Solve lmeds.computeModel(); return arrayFromRotation(lmeds.model_coefficients_); } } // namespace relative_pose namespace triangulation { py::object triangulate( pyarray_d &b1, pyarray_d &b2, pyarray_d &t12, pyarray_d &R12 ) { pyopengv::relative_pose::CentralRelativeAdapter adapter(b1, b2, t12, R12); opengv::points_t points; for (size_t i = 0; i < adapter.getNumberCorrespondences(); ++i) { opengv::point_t p = opengv::triangulation::triangulate(adapter, i); points.push_back(p); } return arrayFromPoints(points); } py::object triangulate2( pyarray_d &b1, pyarray_d &b2, pyarray_d &t12, pyarray_d &R12 ) { pyopengv::relative_pose::CentralRelativeAdapter adapter(b1, b2, t12, R12); opengv::points_t points; for (size_t i = 0; i < adapter.getNumberCorrespondences(); ++i) { opengv::point_t p = opengv::triangulation::triangulate2(adapter, i); points.push_back(p); } return arrayFromPoints(points); } } // namespace triangulation } // namespace pyopengv PYBIND11_MODULE(pyopengv, m) { namespace py = pybind11; m.def("absolute_pose_p2p", pyopengv::absolute_pose::p2p); m.def("absolute_pose_p3p_kneip", pyopengv::absolute_pose::p3p_kneip); m.def("absolute_pose_p3p_gao", pyopengv::absolute_pose::p3p_gao); m.def("absolute_pose_gp3p", pyopengv::absolute_pose::gp3p); m.def("absolute_pose_epnp", pyopengv::absolute_pose::epnp); m.def("absolute_pose_gpnp", pyopengv::absolute_pose::gpnp); m.def("absolute_pose_upnp", pyopengv::absolute_pose::upnp); m.def("absolute_pose_optimize_nonlinear", pyopengv::absolute_pose::optimize_nonlinear); m.def("absolute_pose_ransac", pyopengv::absolute_pose::ransac, py::arg("v"), py::arg("p"), py::arg("algo_name"), py::arg("threshold"), py::arg("iterations") = 1000, py::arg("probability") = 0.99 ); m.def("absolute_pose_lmeds", pyopengv::absolute_pose::lmeds, py::arg("v"), py::arg("p"), py::arg("algo_name"), py::arg("threshold"), py::arg("iterations") = 1000, py::arg("probability") = 0.99 ); m.def("relative_pose_twopt", pyopengv::relative_pose::twopt); m.def("relative_pose_twopt_rotation_only", pyopengv::relative_pose::twopt_rotationOnly); m.def("relative_pose_rotation_only", pyopengv::relative_pose::rotationOnly); m.def("relative_pose_fivept_nister", pyopengv::relative_pose::fivept_nister); m.def("relative_pose_fivept_kneip", pyopengv::relative_pose::fivept_kneip); m.def("relative_pose_sevenpt", pyopengv::relative_pose::sevenpt); m.def("relative_pose_eightpt", pyopengv::relative_pose::eightpt); m.def("relative_pose_eigensolver", pyopengv::relative_pose::eigensolver); m.def("relative_pose_sixpt", pyopengv::relative_pose::sixpt); m.def("relative_pose_optimize_nonlinear", pyopengv::relative_pose::optimize_nonlinear); m.def("relative_pose_ransac", pyopengv::relative_pose::ransac, py::arg("b1"), py::arg("b2"), py::arg("algo_name"), py::arg("threshold"), py::arg("iterations") = 1000, py::arg("probability") = 0.99 ); m.def("relative_pose_lmeds", pyopengv::relative_pose::lmeds, py::arg("b1"), py::arg("b2"), py::arg("algo_name"), py::arg("threshold"), py::arg("iterations") = 1000, py::arg("probability") = 0.99 ); m.def("relative_pose_ransac_rotation_only", pyopengv::relative_pose::ransac_rotationOnly, py::arg("b1"), py::arg("b2"), py::arg("threshold"), py::arg("iterations") = 1000, py::arg("probability") = 0.99 ); m.def("relative_pose_lmeds_rotation_only", pyopengv::relative_pose::lmeds_rotationOnly, py::arg("b1"), py::arg("b2"), py::arg("threshold"), py::arg("iterations") = 1000, py::arg("probability") = 0.99 ); m.def("triangulation_triangulate", pyopengv::triangulation::triangulate); m.def("triangulation_triangulate2", pyopengv::triangulation::triangulate2); } opengv/License.txt0000664016516101651610000000442113344612246013133 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ opengv/.gitmodules0000664016516101651610000000014413635643413013166 0ustar dimadima[submodule "python/pybind11"] path = python/pybind11 url = https://github.com/pybind/pybind11.git opengv/CMakeLists.txt0000664016516101651610000004043513635643413013560 0ustar dimadimacmake_minimum_required(VERSION 3.1.3) project(opengv VERSION 1.0 LANGUAGES CXX) # Set the build type. Options are: # # None (CMAKE_C_FLAGS or CMAKE_CXX_FLAGS used) # Debug (CMAKE_C_FLAGS_DEBUG or CMAKE_CXX_FLAGS_DEBUG) # Release (CMAKE_C_FLAGS_RELEASE or CMAKE_CXX_FLAGS_RELEASE) # RelWithDebInfo (CMAKE_C_FLAGS_RELWITHDEBINFO or CMAKE_CXX_FLAGS_RELWITHDEBINFO) # MinSizeRel (CMAKE_C_FLAGS_MINSIZEREL or CMAKE_CXX_FLAGS_MINSIZEREL) set(CMAKE_BUILD_TYPE Release) #set the default path for built executables to the "bin" directory set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin) #set the default path for built libraries to the "lib" directory set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib) OPTION(BUILD_TESTS "Build tests" ON) OPTION(BUILD_PYTHON "Build Python extension" OFF) IF(MSVC) set(BUILD_SHARED_LIBS OFF) ELSE() OPTION(BUILD_SHARED_LIBS "Build shared libraries" OFF) OPTION(BUILD_POSITION_INDEPENDENT_CODE "Build position independent code (-fPIC)" ON) ENDIF() IF(MSVC) add_compile_options(/wd4514 /wd4267 /bigobj) add_definitions(-D_USE_MATH_DEFINES) ELSE() IF (CMAKE_SYSTEM_PROCESSOR MATCHES "(arm64)|(ARM64)|(aarch64)|(AARCH64)") add_definitions (-march=armv8-a) ELSEIF (CMAKE_SYSTEM_PROCESSOR MATCHES "(arm)|(ARM)|(armhf)|(ARMHF)|(armel)|(ARMEL)") add_definitions (-march=armv7-a) ELSE () add_definitions (-march=native) #TODO use correct c++11 def once everybody has moved to gcc 4.7 # for now I even removed std=gnu++0x ENDIF() add_definitions ( -O3 -Wall -Wextra #-Werror -Wwrite-strings -Wno-unused-parameter -fno-strict-aliasing ) ENDIF() IF(BUILD_POSITION_INDEPENDENT_CODE) add_definitions( -fPIC ) ENDIF() set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${PROJECT_SOURCE_DIR}/modules/") find_package(Eigen REQUIRED) set(ADDITIONAL_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS} ${EIGEN_INCLUDE_DIR}/unsupported) set( OPENGV_SOURCE_FILES src/absolute_pose/modules/main.cpp src/absolute_pose/modules/gp3p/code.cpp src/absolute_pose/modules/gp3p/init.cpp src/absolute_pose/modules/gp3p/reductors.cpp src/absolute_pose/modules/gp3p/spolynomials.cpp src/absolute_pose/modules/Epnp.cpp src/absolute_pose/modules/gpnp1/code.cpp src/absolute_pose/modules/gpnp1/init.cpp src/absolute_pose/modules/gpnp1/reductors.cpp src/absolute_pose/modules/gpnp1/spolynomials.cpp src/absolute_pose/modules/gpnp2/code.cpp src/absolute_pose/modules/gpnp2/init.cpp src/absolute_pose/modules/gpnp2/reductors.cpp src/absolute_pose/modules/gpnp2/spolynomials.cpp src/absolute_pose/modules/gpnp3/code.cpp src/absolute_pose/modules/gpnp3/init.cpp src/absolute_pose/modules/gpnp3/reductors.cpp src/absolute_pose/modules/gpnp3/spolynomials.cpp src/absolute_pose/modules/gpnp4/code.cpp src/absolute_pose/modules/gpnp4/init.cpp src/absolute_pose/modules/gpnp4/reductors.cpp src/absolute_pose/modules/gpnp4/spolynomials.cpp src/absolute_pose/modules/gpnp5/code.cpp src/absolute_pose/modules/gpnp5/init.cpp src/absolute_pose/modules/gpnp5/reductors.cpp src/absolute_pose/modules/gpnp5/spolynomials.cpp src/absolute_pose/modules/upnp2.cpp src/absolute_pose/modules/upnp4.cpp src/relative_pose/modules/main.cpp src/relative_pose/modules/fivept_nister/modules.cpp src/relative_pose/modules/fivept_stewenius/modules.cpp src/relative_pose/modules/fivept_kneip/code.cpp src/relative_pose/modules/fivept_kneip/init.cpp src/relative_pose/modules/fivept_kneip/reductors.cpp src/relative_pose/modules/fivept_kneip/spolynomials.cpp src/relative_pose/modules/sixpt/modules2.cpp src/relative_pose/modules/eigensolver/modules.cpp src/relative_pose/modules/ge/modules.cpp src/math/cayley.cpp src/math/quaternion.cpp src/math/arun.cpp src/math/Sturm.cpp src/math/roots.cpp src/math/gauss_jordan.cpp src/absolute_pose/methods.cpp src/absolute_pose/CentralAbsoluteAdapter.cpp src/absolute_pose/NoncentralAbsoluteAdapter.cpp src/absolute_pose/NoncentralAbsoluteMultiAdapter.cpp src/relative_pose/methods.cpp src/relative_pose/CentralRelativeAdapter.cpp src/relative_pose/CentralRelativeWeightingAdapter.cpp src/relative_pose/NoncentralRelativeAdapter.cpp src/relative_pose/CentralRelativeMultiAdapter.cpp src/relative_pose/NoncentralRelativeMultiAdapter.cpp src/triangulation/methods.cpp src/point_cloud/methods.cpp src/point_cloud/PointCloudAdapter.cpp src/sac_problems/absolute_pose/AbsolutePoseSacProblem.cpp src/sac_problems/absolute_pose/MultiNoncentralAbsolutePoseSacProblem.cpp src/sac_problems/relative_pose/CentralRelativePoseSacProblem.cpp src/sac_problems/relative_pose/NoncentralRelativePoseSacProblem.cpp src/sac_problems/relative_pose/RotationOnlySacProblem.cpp src/sac_problems/relative_pose/TranslationOnlySacProblem.cpp src/sac_problems/relative_pose/EigensolverSacProblem.cpp src/sac_problems/relative_pose/MultiCentralRelativePoseSacProblem.cpp src/sac_problems/relative_pose/MultiNoncentralRelativePoseSacProblem.cpp src/sac_problems/point_cloud/PointCloudSacProblem.cpp src/absolute_pose/MACentralAbsolute.cpp src/absolute_pose/MANoncentralAbsolute.cpp src/relative_pose/MACentralRelative.cpp src/relative_pose/MANoncentralRelative.cpp src/relative_pose/MANoncentralRelativeMulti.cpp src/point_cloud/MAPointCloud.cpp ) set( OPENGV_HEADER_FILES include/opengv/types.hpp include/opengv/OptimizationFunctor.hpp include/opengv/absolute_pose/methods.hpp include/opengv/relative_pose/methods.hpp include/opengv/triangulation/methods.hpp include/opengv/point_cloud/methods.hpp include/opengv/math/cayley.hpp include/opengv/math/quaternion.hpp include/opengv/math/arun.hpp include/opengv/math/Sturm.hpp include/opengv/math/roots.hpp include/opengv/math/gauss_jordan.hpp include/opengv/absolute_pose/AbsoluteAdapterBase.hpp include/opengv/absolute_pose/CentralAbsoluteAdapter.hpp include/opengv/absolute_pose/NoncentralAbsoluteAdapter.hpp include/opengv/absolute_pose/NoncentralAbsoluteMultiAdapter.hpp include/opengv/absolute_pose/AbsoluteMultiAdapterBase.hpp include/opengv/relative_pose/RelativeAdapterBase.hpp include/opengv/relative_pose/RelativeMultiAdapterBase.hpp include/opengv/relative_pose/CentralRelativeAdapter.hpp include/opengv/relative_pose/CentralRelativeWeightingAdapter.hpp include/opengv/relative_pose/NoncentralRelativeAdapter.hpp include/opengv/relative_pose/CentralRelativeMultiAdapter.hpp include/opengv/relative_pose/NoncentralRelativeMultiAdapter.hpp include/opengv/point_cloud/PointCloudAdapterBase.hpp include/opengv/point_cloud/PointCloudAdapter.hpp include/opengv/sac_problems/absolute_pose/AbsolutePoseSacProblem.hpp include/opengv/sac_problems/absolute_pose/MultiNoncentralAbsolutePoseSacProblem.hpp include/opengv/sac_problems/relative_pose/CentralRelativePoseSacProblem.hpp include/opengv/sac_problems/relative_pose/NoncentralRelativePoseSacProblem.hpp include/opengv/sac_problems/relative_pose/MultiCentralRelativePoseSacProblem.hpp include/opengv/sac_problems/relative_pose/MultiNoncentralRelativePoseSacProblem.hpp include/opengv/sac_problems/relative_pose/EigensolverSacProblem.hpp include/opengv/sac_problems/relative_pose/RotationOnlySacProblem.hpp include/opengv/sac_problems/relative_pose/TranslationOnlySacProblem.hpp include/opengv/sac_problems/point_cloud/PointCloudSacProblem.hpp include/opengv/absolute_pose/MACentralAbsolute.hpp include/opengv/absolute_pose/MANoncentralAbsolute.hpp include/opengv/relative_pose/MACentralRelative.hpp include/opengv/relative_pose/MANoncentralRelative.hpp include/opengv/relative_pose/MANoncentralRelativeMulti.hpp include/opengv/point_cloud/MAPointCloud.hpp ) add_library( opengv ${OPENGV_SOURCE_FILES} ${OPENGV_HEADER_FILES} ) add_library( random_generators test/random_generators.cpp test/random_generators.hpp test/experiment_helpers.cpp test/experiment_helpers.hpp test/time_measurement.cpp test/time_measurement.hpp ) set_target_properties( opengv random_generators PROPERTIES SOVERSION ${PROJECT_VERSION} VERSION ${PROJECT_VERSION} CXX_STANDARD 11 CXX_STANDARD_REQUIRED ON DEBUG_POSTFIX d ) target_include_directories( opengv PUBLIC # only when building from the source tree $ # only when using the lib from the install path $ ${ADDITIONAL_INCLUDE_DIRS} ) target_include_directories( random_generators PRIVATE ${ADDITIONAL_INCLUDE_DIRS} ) target_link_libraries( random_generators opengv ) IF (BUILD_TESTS) enable_testing() include_directories( ${ADDITIONAL_INCLUDE_DIRS} ) add_executable( test_absolute_pose test/test_absolute_pose.cpp ) target_link_libraries( test_absolute_pose opengv random_generators ) add_test(NAME test_absolute_pose WORKING_DIRECTORY ${EXECUTABLE_OUTPUT_PATH} COMMAND test_absolute_pose) add_executable( test_absolute_pose_sac test/test_absolute_pose_sac.cpp ) target_link_libraries( test_absolute_pose_sac opengv random_generators ) add_test(NAME test_absolute_pose_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_absolute_pose_sac) add_executable( test_noncentral_absolute_pose test/test_noncentral_absolute_pose.cpp ) target_link_libraries( test_noncentral_absolute_pose opengv random_generators ) add_test(NAME test_noncentral_absolute_pose WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_noncentral_absolute_pose) add_executable( test_noncentral_absolute_pose_sac test/test_noncentral_absolute_pose_sac.cpp ) target_link_libraries( test_noncentral_absolute_pose_sac opengv random_generators ) add_test(NAME test_noncentral_absolute_pose_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_noncentral_absolute_pose_sac) add_executable( test_multi_noncentral_absolute_pose_sac test/test_multi_noncentral_absolute_pose_sac.cpp ) target_link_libraries( test_multi_noncentral_absolute_pose_sac opengv random_generators ) add_test(NAME test_multi_noncentral_absolute_pose_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_multi_noncentral_absolute_pose_sac) add_executable( test_relative_pose test/test_relative_pose.cpp ) target_link_libraries( test_relative_pose opengv random_generators ) add_test(NAME test_relative_pose WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_relative_pose) add_executable( test_relative_pose_rotationOnly test/test_relative_pose_rotationOnly.cpp ) target_link_libraries( test_relative_pose_rotationOnly opengv random_generators ) add_test(NAME test_relative_pose_rotationOnly WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_relative_pose_rotationOnly) add_executable( test_relative_pose_rotationOnly_sac test/test_relative_pose_rotationOnly_sac.cpp ) target_link_libraries( test_relative_pose_rotationOnly_sac opengv random_generators ) add_test(NAME test_relative_pose_rotationOnly_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_relative_pose_rotationOnly_sac) add_executable( test_relative_pose_sac test/test_relative_pose_sac.cpp ) target_link_libraries( test_relative_pose_sac opengv random_generators ) add_test(NAME test_relative_pose_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_relative_pose_sac) add_executable( test_noncentral_relative_pose test/test_noncentral_relative_pose.cpp ) target_link_libraries( test_noncentral_relative_pose opengv random_generators ) add_test(NAME test_noncentral_relative_pose WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_noncentral_relative_pose) add_executable( test_noncentral_relative_pose_sac test/test_noncentral_relative_pose_sac.cpp ) target_link_libraries( test_noncentral_relative_pose_sac opengv random_generators ) add_test(NAME test_noncentral_relative_pose_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_noncentral_relative_pose_sac) add_executable( test_multi_noncentral_relative_pose_sac test/test_multi_noncentral_relative_pose_sac.cpp ) target_link_libraries( test_multi_noncentral_relative_pose_sac opengv random_generators ) add_test(NAME test_multi_noncentral_relative_pose_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_multi_noncentral_relative_pose_sac) add_executable( test_eigensolver_sac test/test_eigensolver_sac.cpp ) target_link_libraries( test_eigensolver_sac opengv random_generators ) add_test(NAME test_eigensolver_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_eigensolver_sac) add_executable( test_triangulation test/test_triangulation.cpp ) target_link_libraries( test_triangulation opengv random_generators ) add_test(NAME test_triangulation WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_triangulation) add_executable( test_eigensolver test/test_eigensolver.cpp ) target_link_libraries( test_eigensolver opengv random_generators ) add_test(NAME test_eigensolver WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_eigensolver) add_executable( test_point_cloud test/test_point_cloud.cpp ) target_link_libraries( test_point_cloud opengv random_generators ) add_test(NAME test_point_cloud WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_point_cloud) add_executable( test_point_cloud_sac test/test_point_cloud_sac.cpp ) target_link_libraries( test_point_cloud_sac opengv random_generators ) add_test(NAME test_point_cloud_sac WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_point_cloud_sac) add_executable( test_Sturm test/test_Sturm.cpp ) target_link_libraries( test_Sturm opengv random_generators ) add_test(NAME test_Sturm WORKING_DIRECTORY ${CMAKE_RUNTIME_OUTPUT_DIRECTORY} COMMAND test_Sturm) set_target_properties( test_absolute_pose test_absolute_pose_sac test_noncentral_absolute_pose test_noncentral_absolute_pose_sac test_multi_noncentral_absolute_pose_sac test_relative_pose test_relative_pose_rotationOnly test_relative_pose_rotationOnly_sac test_relative_pose_sac test_noncentral_relative_pose test_noncentral_relative_pose_sac test_multi_noncentral_relative_pose_sac test_eigensolver_sac test_triangulation test_eigensolver test_point_cloud test_point_cloud_sac test_Sturm PROPERTIES CXX_STANDARD 11 CXX_STANDARD_REQUIRED ON DEBUG_POSTFIX d ) ENDIF() # Configuration set(config_install_dir "lib/cmake/${PROJECT_NAME}-${PROJECT_VERSION}") set(include_install_dir "include") set(version_config "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake") set(project_config "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake") set(targets_export_name "${PROJECT_NAME}Targets") # Include module with fuction 'write_basic_package_version_file' include(CMakePackageConfigHelpers) # Configure 'ConfigVersion.cmake' # Note: PROJECT_VERSION is used as a VERSION write_basic_package_version_file( "${version_config}" COMPATIBILITY SameMajorVersion ) # Configure 'Config.cmake' # Use variables: # * targets_export_name # * PROJECT_NAME configure_package_config_file( "modules/Config.cmake.in" "${project_config}" INSTALL_DESTINATION "${config_install_dir}") # Export 'Targets.cmake' to build dir (to find package in build dir without install) export(TARGETS opengv FILE "${CMAKE_CURRENT_BINARY_DIR}/${targets_export_name}.cmake") # Targets: install(TARGETS opengv EXPORT "${targets_export_name}" LIBRARY DESTINATION "lib" ARCHIVE DESTINATION "lib" RUNTIME DESTINATION "bin" INCLUDES DESTINATION "${include_install_dir}") # Config # * /lib/cmake/opengv/opengvConfig.cmake # * /lib/cmake/opengv/opengvConfigVersion.cmake install(FILES "${project_config}" "${version_config}" DESTINATION "${config_install_dir}") # Config # * /lib/cmake/opengv/opengvTargets.cmake install(EXPORT "${targets_export_name}" NAMESPACE "${namespace}" DESTINATION "${config_install_dir}") # Headers install(DIRECTORY include/ DESTINATION ${include_install_dir} FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp") if (BUILD_PYTHON) add_subdirectory( python ) endif() opengv/doc/0000775016516101651610000000000013344612246011554 5ustar dimadimaopengv/doc/addons/0000775016516101651610000000000013635643413013027 5ustar dimadimaopengv/doc/addons/04_how_to_contribute.dox0000664016516101651610000001335413344612246017606 0ustar dimadima/** \page page_how_to_contribute How to contribute * * You are missing your geometric vision algorithm? You share the feeling that it would be nice to have a common place for all geometric vision algorithms, which then implicitly would offer automatic benchmarking without having to do the overhead everyime? Well, that place is here! Join the community today and add your algorithm(s). The instructions on this page give you some additional hints if you want to participate. * * \section sec_contribute_1 Preparations * * If you haven't done so, please follow the instructions in the "Installation"-section to install the library on your system. We strongly recommend that you are using github's fork/pull request mechanism. * It is also recommended that you first collect some experience with using the library, and notably understand the interface of the library. Please checkout the section "How to use". * * \section sec_contribute_2 Design concepts: * * The library is developped in C++. The interface is based on the adapter-pattern, and you should use this concept in order to keep things as compatible as possible. In essence, it means that you should reuse the base-classes AbsoluteAdapterBase and RelativeAdapterBase, no matter if implementing a new algorithm or if extending the portability by implementing a new adapter. Have a look at the "How to use"-section in order to get more information. * * You should also make yourself familiar with some coding standards. The code written so far doesn't necessarily follow one standard exclusively, but at least reflects the effort of maintaining a reasonable level of consistency. Please try to follow that line, it will substantially facilitate the inclusion of your code. Also have a look at the directory structure, it strictly follows the namespace structure, and this should remain the case. Headers that are only intended for internal use are in sub-folders called "modules", and templated implementation-headers go into sub-directories called "implementation". Also have a look at types.hpp, these are the types used for all geometric vision constructs, and should be reused thoughout the entire library. OpenGV uses two-space indentation, and tries to stick to 80-column width. * * Another property that should be maintened is "independence". The library essentially depends only on Eigen. This is a powerful library that should deliver most of the functionality required for the purpose of opengv. For the sake of simplicity of installation and contribution, we should keep things along these lines, which means that it is appreciated if algorithms do not require the inclusion of any further third-party libraries. * * The files in the library are encoded with UTF-8. It has been mainly developed under Linux, and compilation with gcc currently returns no warnings (hopefully). If you plan to develop under Windows, make sure you use an editor that understands UTF-8 encoding (no, notepad.exe is not a nice editor ;) ). * * \section sec_contribute_3 Todos: * * The following is a non-exhaustive list of things that could be improved. * You may also want to contact kneip.laurent@gmail.com for further information, if you want to * collaborate on one of these points. * *
    *
  • The library should easily permit further benchmarks, for instance all the special cases (e.g. planar structure etc.). *
  • The triangulation method needs to be able to handle non-central viewpoints. This would avoid some hacks here and there. Same accounts for the point-cloud alignment methods. *
  • The triangulation methods (and possibly further algorithms) should be included in the opengv-Matlab-interface. *
  • NoncentralRelativePoseSacProblem could decide automatically whether it should process data in a central or non-central way. Same accounts for the MultiNoncentralRelativePoseSacProblem. *
  • Sometimes ransac or iterative methods reset the adapter transformation for instance to compute reprojection errors (search recursively for sett). The original value should always be reset, because other parts of the algorithm potentially want to use it. *
  • Add more adapters to increase the portability. Examples are: OpenCV, Gandalf, VXR, Bundler, libcvd, OpenMVG. *
  • There is an improved version of p3p_kneip lying around somewhere, which could be included. *
  • Richard Hartley's implementation of the five-point should be included (replacing the current one). *
  • Hongdong Li's five-point solver should be included. *
  • Kukelova's polynomial eigenvalue solution could be included. *
  • P4P and DLT should be included. *
  • What about DLS and OPnP? Only Matlab versions are publically available. *
  • The 6-point by Stewenius is extremly difficult to reimplement. The reimplementation I provide is maybe not the best. *
  • Most of the current implementations treat the correspondences equally. The AdapterBase-classes however contain already a virtual function called "getWeight", which could be used to weight the correspondences differently for instance in a non-linear optimization scheme. Most of the adapters currently simply return 1.0 for these calls. Only the CentralRelativeWeightingAdapter has constructors that include the weight of the correspondences. *
  • arun_complete and threept_arun are redundant, we should get rid of one of them. *
  • The polynomial structures are Matlab-like arrays of coefficients, of different types, and sometimes with different conventions (coefficients once stored along the lines, once along the columns). *
  • Add more comments in implementation files such that users can potentially understand what's going on. *
  • Use vector.segment, block...topleftcorner etc. *
  • Theia by Chris Sweeney has an interesting Sturm root finder, it could be transplanted. *
* */ opengv/doc/addons/mainpage.dox0000664016516101651610000001526713344612246015334 0ustar dimadima/** \mainpage The OpenGV library * * Important note: If you are only interested in using the library under Matlab, now there is a precompiled mex-library for 64-bit systems available. You can download it from: * \verbatim Windows: http://laurentkneip.github.io/publications/opengv.mexw64 Mac OSX: http://laurentkneip.github.io/publications/opengv.mexmaci64 \endverbatim * * These versions have been added around March 2016, so please be aware that later additions may not be included in this distribution. You can go immediately to \ref page_matlab "Use under Matlab" to receive further instructions on the Matlab interface. * * The OpenGV library aims at unifying geometric computer vision algorithms for calibrated camera pose computation within a single * efficient C++-library. OpenGV stands for Open Geometric Vision. It contains classical central and more recent non-central absolute * and relative camera pose computation algorithms, as well as triangulation and point-cloud alignment functionalities, all extended * by non-linear optimization and RANSAC contexts. It contains a flexible C++-interface as well as Matlab and Python wrappers, and eases the * comparison of different geometric vision algorithms. A benchmark to compare the various solutions for one particular problem against * each other is included in the Matlab stuff. * * The library is described in the paper (Please cite if you use it for your research!): * * - L. Kneip, P. Furgale, "OpenGV: A unified and generalized approach to real-time calibrated geometric vision", Proc. of The IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China. May 2014. * * The library has been developped in the context of the following papers. * * - L. Kneip, D. Scaramuzza, R. Siegwart, "A Novel Parametrization of the Perspective-Three-Point Problem for a Direct Computation of Absolute Camera Position and Orientation", Proc. of The IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Colorado Springs, USA. June 2011. * - L. Kneip, M. Chli, R. Siegwart, "Robust Real-Time Visual Odometry with a Single Camera and an IMU", Proc. of The British Machine Vision Conference (BMVC), Dundee, UK. August 2011. * - T. Kazik, L. Kneip, J. Nikolic, M. Pollefeys, R. Siegwart, "Real-Time 6D Stereo Visual Odometry with Non-Overlapping Fields of View", Proc. of The IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Providence, USA. June 2012. * - L. Kneip, R. Siegwart, M. Pollefeys, "Finding the Exact Rotation Between Two Images Independently of the Translation", Proc. of The European Conference on Computer Vision (ECCV), Florence, Italy. October 2012. * - L. Kneip, P. Furgale, R. Siegwart, "Using Multi-Camera Systems in Robotics: Efficient Solutions to the NPnP Problem", Proc. of The IEEE International Conference on Robotics and Automation (ICRA), Karlsruhe, Germany. May 2013. * - L. Kneip, S. Lynen, "Direct Optimization of Frame-to-Frame Rotation", Proc. of The International Conference on Computer Vision (ICCV), Sydney, Australia. December 2013. * - L. Kneip, H. Li, "Efficient Computation of Relative Pose for Multi-Camera Systems", In Proc. of the IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Columbus, USA. June 2014. * - L. Kneip, H. Li, Y. Seo, "UPnP: An optimal O(n) solution to the absolute pose problem with universal applicability", In Proc. of The European Conference on Computer Vision (ECCV), Zurich, Switzerland. September 2014. * * Please cite the OpenGV paper as well as the corresponding paper if you use OpenGV to work on a particular problem. * * \section main_sec_2 Getting started * * OpenGV features the following set of algorithms: * *
    *
  • Absolute camera pose computation: *
      *
    1. absolute pose computation with known rotation *
    2. two P3P-algorithms (Kneip, Gao) *
    3. generalized P3P *
    4. the EPnP algorithm by Lepetit and Fua *
    5. an extension of the EPnP algorithm to the non-central case (Kneip) *
    6. the generalized absolute pose solver presented at ICRA 2013 (Kneip) *
    7. non-linear optimization over n correspondences (both central and non-central) *
    8. the UPnP algorithm presented at ECCV 2014 (both central and non-central, and minimal and non-minimal) *
    *
  • Relative camera-pose computation: *
      *
    1. 2-point algorithm for computing the translation with known relative rotation *
    2. 2-point algorithm for deriving the rotation in a pure-rotation situation *
    3. n-point algorithm for deriving the rotation in a pure-rotation situation *
    4. 5-point algorithm by Stewenius *
    5. 5-point algorithm by Nister *
    6. 5-point algorithm to solve for rotations directly (by Kneip) *
    7. 7-point algorithm *
    8. 8-point algorithm by Longuet-Higgins *
    9. 6-point algorithm by Henrik Stewenius for generalized relative pose *
    10. 17-point algorithm by Hongdong Li *
    11. non-linear optimization over n correspondences (both central and non-central) *
    12. relative rotation as an iterative eigenproblem (by Kneip) *
    13. generalized reltive rotation for multi-camera systems as an iterative eigenproblem (by Kneip) *
    *
  • Two methods for point-triangulation *
  • Arun's method for aligning point clouds *
  • Generic sample-consensus problems for most algorithms useable with Ransac *
  • Math tools: *
      *
    1. Generic Sturm-sequence implementation for numerical root-finding *
    2. Algebraic root finding *
    3. Cayley rotations *
    *
  • Unit/Benchmarking tests for all algorithms *
  • Matlab interface *
  • Python interface *
* * The aim of OpenGV is to make these algorithms accessible * to real-time computer vision and robotics-related tasks, that require efficient * pose computation of calibrated cameras. It is also intended to serve as a * benchmarking framework for testing and comparing different solutions * to geometric-vision problems. The library realizes a clean separation between * 2D-2D, 2D-3D, and 3D-3D registration tasks. It thus provides * a somewhat missing block between image-processing libraries (e.g. OpenCV) and * more exhaustive non-linear optimization frameworks (e.g. g2o, ceres). By * working exclusively with 3D unit bearing-vectors, it allows to be applied in * conjunction with any optical projection system. * * Please consult the following sub-pages to get a step-by-step introduction to the library: * - \subpage page_installation "Installation" * - \subpage page_how_to_use "How to use" * - \subpage page_matlab "Use under Matlab" * - \subpage page_how_to_contribute "How to contribute" * - \subpage page_contact "Contact" * - \subpage page_references "References" * */ opengv/doc/addons/images/0000775016516101651610000000000013344612246014271 5ustar dimadimaopengv/doc/addons/images/relative_noncentral.pdf0000664016516101651610000006072513344612246021034 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝ½9–f;²©Ç(b^è›P&Sä*)j½G!B(–ÀéßÞv÷pf–œë qÍÀƒÆX³íÿý™>òÏÄñï¯??þ¯ÿ6þçÿ÷ã¿ÿìãcìòóÿ>ìÿçGYµŸÿë‡JÿüoÿåGó£VÛs´öóÏÜRûØíg^»Ò?ÿøÇÜËþ˜íg+‡×÷)UjŸ«üìs}ä½UЬQË:½8-ôšËÏÿùŸ?Új壭Ÿ-¯ü1ë©ÜV-³Üœ¶Êù©]>ö!óü¨²”þóשÓG«pæGŸ§Äé#óNStú¨º.Pcîþ±hc¯}šž»|ŒS£¤J¿>z‡>߭ߘk©›%÷tjÎó[o.ù£Ô7=¯ßNmË#Õæ¨#Ëù£›³ó™8ç—œ•Ϩþl-ŸÑÝêÇß0^UÎHåü-çþé»Ö_œRƒðæ”B™C÷^<»CïÄGŸ® OE/iºÆYyCŸÉ:ä8SX/’òg…Õñü}žoê&{†gÕòüãö×™êi΢Àj1QgêY+K_sèÅ”«†9ùL±?s µÏH«…3åü}íhñ,­¾E1Z8XÅË«¨SE‹&Ÿ†X k,/·³ sóWiÊòé\HiB×ʰõδhAOCOщò‘¨Ñ¢×ø¼I~ýøécÌ9Ï—ýý?l«r~óLI­go.vÕÅ({°ÔÎ,Ÿ¥·}ÖH׈ž‘Í7}:•ÏÜäþ”8{ÿ#¯§…‹öOPábœU­ïêÙMZ&ñAŸW'îW¯£…Ï_Ágÿ÷Vÿäóàú7ýüÿqäè¿ñ§å³ù>ÎqtvAE üy8ä¶ævå‘<Áy$QnçÐ:âò¢ýÈõˆöVžõìÎÖŸ.:~ƒçȪDhɰ÷óAŸW/îW¿£…/ßÁºý÷ý¶ï™Ó×#°áŽÙ>FáëF—Ì?œÁù“Çiw©Äârrhγ<Îa’õqãtõlµÃ9ËGÐçL˜n¨èïºCQƒƒFwËçç’uþ=§ÿœ­«'.åÏí†Áxü»u ‰¦âµœqŽ Q®ZZ¦gýœ¡zsÎo¦¦Z]7×/œ×žþíåÁÞíl¤É.¿8ã,)–ì¹#ˆFItøÐç}ÁÏœ3l{ä%ñ2ê¶(Ë:Pó8÷¹ÍÈ•{ÜùñÂÛ@5’ÊBÒ<Ûmy"ªðN9äYËž^,±'{ïtvì{8´bK»iÉ]âŸgZMû—¦w«yEž?è³Fóü#ÛTá”\Ïü¡KÁkþ{‰gŒ~l³wÏ€,‹EQÓË]û¡†3«e?%æyx«±6;0Ï‹#Khwh3ëq¤ÅöÜÄä9»ëϯ“ÉÜÏ®9gÌ+‡Ôá,š;}ZKEÒùÐMÏ¥T:{¬òàYz€$Ž” gêå–ÎÂ<Ï…Cï‘GPðç¢WÎÕ©ÒDÑŽ?ô‘wEW­tº6Û¡+@…Ž;Œ¦‹Rê+Ѽ|Ò ¸h*ðÌ-O‰|ÆN=”ähùüp£3Ä:[®J•MâárVë„Õ/ë‹®y­Á9m.ˆu!¬j>ëSOŸ#kÏ4Uº¢Ó¨Q—ïJ>O/«¯&oŸ3^gQU>ÏßÏÞ8c~8dç3r©¦ó=õ|fc¡Ötú’õ‰Cœç׃wNæ„;gB²•›Öتí§Äi›Á…ÖàÖÉÉwèzMgdñoð–K\ ÔB׋,åá^RÓó—Qª¸Äš.±¢MÞ¾)K¬:sÚ¨j–Ã9këÌh–L:cÆãšÛ5¿í ¼8|)(jtjœõ¬EÃꤗgÝjƒ‰C7ÏBŸQ`ò“Ùïé›>’®·»Bûyž:,ÿÐÊ=NcpÞœ®ËÌïu7”ß0®:us©(¯v/NEùRûUÉKv"‰Þœ¬…øÛ›¹¯¯œ×öþírdÚYÈG(j¿_ wüÐ…MYØ`Þb'tæa8§b:c.¼x}f—­SXÞ‡¬nà\¡²§fê¶Zó9ž'‹1K­)9´N²CŸCÃkR:¨ó±Ûö{4´dëMJ HGõ¨3èÂJµDòv—tn,#}ÔÞžû#Άª(¿R~æ>Ÿ+Æ~M}eÿíY™‰õ„lâ#ÎþŸÚ½Õ»âH±]oš6ΤÖþ*qžšsy¿«—g<µ›ÏñÓ½Ó–NÓšV¹‰¹:r`ôŸ_&Soªuzœõ–О{Ÿ«hÖ ¢Æ©~s¬6<œÕ|ÿ†s×Z\t¢Ù‹ì\7£|Ѥ³¸ÇgÎYbĺs½0':û7çþsF…޲rl>©±p’¤Ú’úIÓ˜-õÜG3[ç ÙÚëhÏ8ÕêV†±1X9Òr!Piáì‚©%Âù&yѬØ+Ùk2ùÞ"`Q ºR㜌CmX¾—²$_É+G¸I ™–B s}•Ø^B{n+§oµú’Öy9¿­3…>Q`G—šTdM£*äX@åÜè²ÇióÜ“³åðP…%Üíþjôr¬ÑÂ…X¤–(Gó|Ñð«üa”m5èÙåÌåY‡Sx¼9gþ²ôh„ëú–óÔ:ÿw¶â»esÎ7æêÍáâüs±`È=g@'¿|h½âB³âü[+æ¨û,›V]¯u‘ZÛsÏÒwŠìÌ@nq°I¯ ˆ,ŸÓÚr­DNºJàbzø°˜+׿:!´HÃý¾wl)oű_÷iÍá–þ¾SS´^Gç=’§W»|í‹sÏ7Ÿüã®s^£õݬ:÷ӫжa]Ÿyã «~æ|Úí¿¥àüd”Á“Qi–•uãèí0gZþü8Gè 3‡34n9ëÞyÉunµçˆ=7‹þõ££?7‹3úä}G*—#æ¦-&–§Ý?n…kÙg[œÝrÞëƒuw~.­¯Ã8;îtþ‘V¤c$š·ÙçôÿþçÁo •>ë“ÓøæT^$§ôÈ<ä3 ®oN×µþ÷¾y;´o9w-m‘üjøbŒ¤ûŸ*MVÔát?YÎÙñÛ™Ax1ØGíbŒód§‡ÔÃjpi`‚Æé³DØÈçHKιŸØvfüæ© õ~þÜDOÌÏ`ežt8Ú¹|n~½ótÏкûö~f< Õ(z!öŽFötŠGÀ¤i² ëΓ•Ÿà…E“UC¤5Í›dÛ¾W%klÒSÇòY½çÌe?-nkçÓÏZnºÈ ©95àHž¹L[ÿrsèŒîgh×'Zóê±®ÃWÀÓ6wÎ&Ýç™ÆsãWØrn8´j,Ëm”¤;߃±ÁŸC¦5Zè:cðè¹Ü´T^ÚW ŒèîÅæ¨8¸s[+þÍ–ýð;käZgþ * 3†ùšžª÷Ä/žî§e]æµ,Ï3=–ŒFýÐR–41MP?ÄÝ’ýsèÊ”7{~‘×ãõæä#û÷5ºK›åoεîJ_Én¿µvá]zFAŠå‹s¾Z×âS‹œ÷7œ§Öµ ï†?ou.tˆ¡Æ½yɸ??ÐQ¢½ÙgÖ3Ëáfäê“©-¾ß0î*¹kr®VŽUŠW%MO¢ÏŒ¦7õ©ÄDm«ÎÜnôöoÎóKÿñxž_~ÕÆ‚ó¯G’ê>qÎÖðòhéÖR—Ê´"ZZÀónççt»=]mYõÎ"¨:~î¶ o^–4Æ£KÈî!L[K¦”¯à纠‡Ü¹˜ædíÍÙc¬+·Î]‹Öªàs£p'w’VDEZÒm¢Ï)e/¥ª”.}ûÉrš.Vyv|>êø?º:i¬¸ïq%áUsZÛt‡úœÝ*üX¸§œU8Ï‹¦nj²ÒÕiyôûÇÚG:ð¸^C‡±~òƒ Ï‘$ØÏEjé—Ï­aø—¿Žd>­Q«çßVbžŠ4® ÃΖ™“å!¦Ü<’çŽ{dR°Y5ô¿¼Èþú­šÎ_´ ;'ÅïϯŠ)O¬4·ŠN}lC/i"S®§zïò¯>ö¶[s]|)Œ3ekt={<³ìWâBÖ_Æ[wÔâAž¨OOt‹•7ÔÍÁÀ(q°Îù•ËþŽóÔÂxݧ[ÖɽÐãhˬºdHy~|wÍw37çþ©õÌÿ›¡:´òu ظ›ÿ=ë²£oÉ,é,Çi…ŒMl§zÈwó!ú-'jí³hxšDÃCNhW]ÚÏ·h$nÆà,ƒ±|Èu¼FÜêÕß¿9÷ý‡W3'Àö5÷ƒ¾yKôåÖl¹ô‹#vûõ§£¼;ŒæÇx0zJ²“ÐH—†âoΫÆK½©m‰“lcKËÓÌ?„U¬ç÷Oc@.Ÿ~;8¯ŸâI×Ç7œS«[f} Î8ç;J=–ø’–ô\¦u.ç÷‹Óô–gÛ²OÙå úS.‹²`OyP:ÔM2óã-ˆpÆÚ— mrµÆ:ˆòAtçmE­[€Ü-1iŸw:Ï›Cëqèžhî}™&³G{%»oœ[•:É~Æ\xîúúüuøÃÆï,)8ËŽ%›ö•äÐÝß:wˆn[v‰&°*2î67Ùì,ðÐR«FpØ£ÕMÚ/ж~ô\(åÜh׎l/É…ˆÄˆ›¤ó?´T»g\ª<]Mj ²â*pÞ&œãÐX¢ê—þýpÎqCϬCÝ¡«ÔÒž]z`·‚>¥Ú'«D×¢¶33ÝúÁ~uɯÛÉٞò_— ±C5ÐõQ]ÎOv™tµÄ¤û޳š×SK–òѰT³U›iØü;­{äd÷2Ô§®%_ÆF®¨KZ ®¼2Wh]´ª¸t_%XÍó›òÙáüˆÁì^U-‡+h¶[Aó`'“Üc‚lëÃöñ‹ÿ&GгÄü ãlZn5«êœŒöÕçÒmÿ¯RY:Ùíè,NK·~-Âjë¾Ðr*Zžggt{$”æuŸâñ¥Þxîa?l+*ÈòHJòX:ÛuX¨í‰cö\Ù~<Ôd¿÷è-ÏY$Âòþ^6@L< ª'k‡L‘ÏË×Õ¡Óµ]/YeΦWÜ>¿s%ï­7?8—4^œ±Ü\·éw×úýW;/Žâß ã=-UîÝÌ7Uú«½ ´Kø) k\^{?ïo&*8§Z?#À‚­èá¦8Sw¡Ãé–Ö=\¬gð—ÎöÇ‹¼p×€Ô%áÜ^QDþú!#×®Ze<êšJ~ã,É”­’ÔÇ$[µ;s_ÄQ·:" uAí²¡tDuâp_ê®1Ó½Je¤õtH»xß$:¿éòflžÂ?]]Ïo§RšbÖi©ß]jrÚàé‹þÏ ®»éĬ&U±”Ù_­ux8¾àHŒâ[Ï0q³;ë•W8J¹íéÉ‚(hU¾Eg¾¶>SþHIÆ(“¿4{Ï›<‹Dr©97b­dZ×6?Üèôó«\‘®a¬Ý*.ô)èä±'%ØÒ Tø·1Ýãÿâ —íBŠZ¼Ëw~:–¥e>´tßçwôû‡žÖ*««,Ö$ºÌšjss”õn¯‹¦Æ’ãÎ]B³Yü› šs6Nî~} ý†§G%šNæ—NYñ¡Wñ ±Ã«´å <·#W¶æõÄ£·x…VV,>*zðЛíÈÛV…‹|ãšÜ‘¥±_ú5¤fµ_û‡Ë£»“d öËH‹­z³Ÿ’Z(K”†jO¶,©ƒÅ~‚~ÝûÚÅ]ëSÑKÒàæ„V~YHcÖ>]>Ì0Œeï쳡¶âªµôK[XÁ0Ò’Î0#¯e£œÖxnŽgÐr˜2×)|aI>–£†WáðBFOߤø–°!8‹yrùhí ¼O µûUÿˆ¼Z?ýBÛ!]_ÓÕ¿æSäõ­8|âúÆæKÞ=Uî ïQÂá=Žu9Ð$†ù"»µåu×&îEÛ#ÚÇBÚ\>zPìcp÷Òíúl°Û[Na-E.w÷÷ËʾŸ*Eöx ©Ç¯Ôãâ0ñÞs´&M“ôðÞõ=ɯˆUpw!VÉÝÅXG¯/ˆ•vc¬Ä{ b­¾F)Vó=Ž÷j×ûèë~øš'Û¹ã³zši^Œº­f\‚èë7œn?/­¼!_íJlæw+ßp\ëïv8í‡|Qx…®¶÷ŒnpN=^í#,,{ˆSÛý°—Ÿìál(¼ÏøÍ«/Û¨rê:FüR£Ž}ÞwÍf–Ó©C6OÑFrzcZxQW‡°ù~ºú<:Ì3—Α2íÅ:°Dë„““Ü!§wU+þ¹‹¶[˜*ghæÕ€ Ÿ( –u 7«GE÷+FÂí *<؉vç2*ƒÙöK‹­4&Zc[.º²ºl¶•nóâû©›Îà#ÊôÉ’tjiÝæMÿòäõü*qþÍÍ-ñ0Ö–]^?±e ã…±Ââ{žÀƒwNn¾ª`Jåýf³_³ßÞ Ø¬êâQméÄâ”Æ7Œ‘CK=HãþÀãOº!ôLSƒ·Rj6\O÷‹žÚ°]øô¤£¹ãèœÛSpÝ$_Þdw| Œ«E†c/™z=2®±ûmÙ>œ™’ÎG‰•ÓLJîÍä‡ÓqèlI…§%º—OÚoÞúIà†œ˜âKügYKO¯ÂšfØÛ÷I]*½äE5­tiøeè»¶-Ñ;y f¢—tZc’&K†ýBk»WÔ©eÛ´M ¡&ç‹ €ÃµLþ Ý._/Nñ†kRÈJ•6½tÜ}–÷_ Íò tåÙÙSJ'«Ÿµo»íH  ¹PÈèbM8NòZùzÈZ1¾ú ¯äÚ¥s˜¤Pe“A&£ µ3žyÿ=³VŸÚ9… ÇÝ~’qíéã?ŸZn½¿!e›÷ã+×ÙQRÀÚ+†ã …6íAÖûÈÏ?´¦ v„9ø2<õ¹ÖÍ×/¬n¿Ï§KA.OBò|®¤ë#·Â•ŸAØ2“<ÃÁ%÷0†éüä­àìgLkÚbšî1W ×Dß¿p­„« ×J¹ºx­¥ç#b±]_y-Äk®¥zÓ½–c$Ÿµ®þ²~ÝÆ¦sägÄ'cHhO—òúáhìr¨…:¦”2 ANßÂ3 ¬N³2U° °sÓVY¨ÆÅ‘£D–‚ ›u=(ȦlDÍ¥í21±u)ôLî¾2!uÑS45¶ªO‰­ËeG­B| ù>g8¼}„┡œRÝÉÈ =¤ï¿w¥JZ™¸yàïP£jáð¦›ÙsÎŽ^ë2äµøÐGÒØqsŠÜ´Œ¤ìe©!äG²³¨iu*89pA2& ]¢ÿæ\ºeaífHügÐ*щVM†l_ÛN«eX¶o;köæÀÝjÇG`w¤…ÈmKjÆšϽ—AvdW¯kÅ,Ý>34'-üÀtŒâ™ˆ…#ëø²W &•-÷( ÉAo:$õ¦ïX°2Ž!Rwß8Så8Ë¡'Á»ÏžoRdš:t±«ât\ñÎ^2+Ô¹‡Ñ­Þ:Ï‹Ì#k_™LgI¡i_q(s Ý$aÌÛ"ù•TaÙÿ¸î0ØðæEs@)'od‰ÌfÓØM÷Á¢§+~÷î­Ö§×m·¹b±ã7¬ðåü!ŽtãÑöˆ®¯ÂÔ­ÑŸE÷×?/NÓ(És ÑžÙ¾5ŽÓ*ÒÔ?%²LhÓò<%–rõ—æ~ ?a3§[gKŽ•å‘#¿:¦!-mØ<‡¿IÞ‚Œþ*Aú¢Jtì5v‚þ‘*zxè’tÍCñ¶Xª;VkðõL/:kØ­Uw¤m¤ßÜÙÆ–¡+L+‹=–»¹H‰o/Q3$²¤ÁÀü̘)fM\û’q:ΚNJ9w1ŠïÕr`瀨žK!.thæb&³ ˜_çú×?±Þ1¥Rë"9qÛyq¬¤%pMѧSpC85¬!x s©'ëÇ×W⌫#›æ‹nv´~qtÀ÷dÏÁ™–³‚±¤ªkŒP6 _’*Ûö4uÑzåâ1í8Ó´ü.a³*ÁœŒù­—V”p˜Õ'ÄçÀÌÓêrVÜM+¨Z.†…40…Ò"m5!¬R×û©¬>-WÀò@‹E?¹ÙÝÁ#˜âãµãݨA(Ò!ï#žéqVvÛvªkÉ2ù×&5 _Ë:b®*ø ppã®rŽ8fMR~ØDÿÝMŠÌ/zçˆã}8SŠwhÌ7YúMû}©V04´‡KÊ8ÇŒìcÂ-6ÚŽé@/NëÙ=€,°ÝÇíŽÍ¿Ú¸ü}Ü]NÑš#ýDSÔ¶LªÑîxÑÔh ÷¼ à $Ô èqM'I Á:b媓Í·ìÈÆ¨¶gG€Ü¶pÔZÆš°ûÖ´[Ó¬a±¥(_ó8„¸ƒ}¨ ÞXùe?óÝë5‘;8S±>^Û£ívk{4¼Äƒ~•0ƒ¾÷f-%~sÄCPXtØârs\wÔ¡sUZú¬…jß¹Y µ(ç€CCwˆ4¡/œ&°*Ûé#Zö½ž].ãr¶ë%›ì·úEz!è:—HE­-Aœ Ñ"Z28¿áØIžY“S\WDlõ¨KaÊ‹‡±¼EÌY¹¼K ¯^aŸÉä™^×tÖNɲFQmœ»|ÄrFÅ”öq µNT®âøÃ\ŸßPpw1;á)Q»½Öy8èí¶.QNˆ¶ì˜Sa®À‘&Ñ./²‡2|«Fpšœ‡Ôæ èÞH/ª¥í˜ÔÎÿ)ì›»AñWo ý)+Èß´F.)Hû*0ÜɤP¦®àf•ß×Hw‹âä[}çf#IصÌ_tÜ:NsŒ'¬úÄSY¥¤Þ45."BŽ&)Ï¿I—ÿí¥ŒÃÝbÑÝY4¯–²âlUÒy!p qÔkFrÙ\{¡kG ÚÂ]*Ó!áa Rr^äÔ7L{v‚V«zé#¨&)mÇ‘—}ß6§s%BG—Ý]4K:èEg ÂqŒÇêÔЩØ">_oý~… 3š%~bDŒ¿ŸÞ„zrró]jAZ•CÇ£²'ÛI\pÝV \¨˜ËVü»XÂvFTëc/ûv2ëÂðh²À({ø¬ëGØÒ»Õɉ£nÞGÓ‹Ö“IËãâØöÂ\_´†sXß%7õ ·še]·7HH­¯rMÛ»"#†Í‡3ýÎ~ÍH®£zâƒR¹é(9?%»%$Kµ]$4ûÕÏR{†_q®êg $²C¡ýœttȧµ 0©/ëevráÖÐbèH”÷SŒ}>ËÖšž¶vµ9ÝKd4‡W B[•ÓŒoIžÎ!›T»4 »¢à‚H}s ÓÄß÷õƒrg=ƒ˜Q«‹×°nIò,o 3îÝ·†">‰j¦º^w=¾^R3´ ÷D²àÆÏ¯S­ƒ.ÛqR‡˜Üã„­©0‡ÞIìG8á‚Ä=çl¨Âí´§ñU›î]h5ÓRÜiðô’ð&Êô ¡âšŒA š‡}ñëûÐ-ÜPÂñ@XM5|)ã7¼›®ÛQ•/N—ò [LQv¨¯ïð‡ÿú:¿?9,`eÁ2…ŒóçÅSýp4´|ñ†Œ,a‘`T<,m:9S4¸Sü4jéù¦·•Jg+^~Ô°€â-&z'ˆÐ й¸.™Cñ[벩ƒýe-jé28éÏÍ€$ª] »æšF$‰i£>Æ""·ŒEBÝyÑqð<”Rí§ZèÝC?¡HŠ.ªƒˆUp\æåkÙ©²¹¶xòB{µ•v05\fjîža AMÍÈ®ƒveëº7j³·Zqðø¡åÙ}ÑÔÀ¨¼KØBÜP.oº[+tsj(ñ¨U §Wè¡iûPµË ª/ü8~òj˶¯ò ÕÖ™:B&ŽM†skåÝ/+]Rع¼àš'"†©è¡¥©"†Ǹv¾!:é‰45 ?õ”Ⱥ3˜¦“ÙQ»Z’Õ5‚³³ÑßçZ®Åýä=çÕ˜Ü2#žªE¨:¢‘ØÒ¬Ún$ÐèåÞ:½Ds½Ç.,ž£x°slík2´:‚ƒ« £¾ç³Iޏ)ï]¢µ–_<@Ÿù†nçP ÓvaÖ†líÉ‹°Ë¿ã»Ë¸õøè´¬o„ÏpØ0â2 Œj«MÇ?83 ËH¬íŠK,´îÕpÞ=€»oÑÄÕrÿü"ºùØ´-l:››jž7ç7œCU 9ð0U>^J­o¯º#¹Á[¼éýúsöÜ ×à¦FÌ·^CXfƒ?©º—¨P[-¿-a|TÚ¬a~;åb÷jéÔX›»{Ô^}u°Ûôú»Ül½  RÎÃ!Ó7JvYÏÏ~n£ƒªcyÏx\ä˜Ö'ß #æ¨Á®…µ¸Á”äVY/ºÓa[U‹Õ"úä!餣r¬Ä™45xe­W‰ê.T-ºéÔ/»^],‚Ë$ËÀE°ëîû¢Ã‘çÅÑüŸéDÊÔéB’R3huêâG›é`â úŽ£ZâÈâjW³ØL¯éÓK–Õ¯/ˆ4Í¡çŠw¦_fÅo/~„ètɾ0Ž:°l¨*]Š)€<> u­ ¡ ?/>š_Í7÷ŠŽA”öÒ`-y¾´d[+ØC¥øĸ[¬nS•U[Ž(Ù§(ŠEÔ9`Z¶K!ñöBÃa± V ‹8üªšÚA(¬î\«(C3âáwd4Åk™@ Äž!T[Žc:é9oÏ¢õʸ|cõ®<Ý ®6霖;ê xöçDzèêwò‹c—3âöWxšl­dÛsØîöÅb-×8³4¿†ºäÕW‰¦ 82Cœ?//<¶`·Ø´¢SpݤDŠ›wYâíj¶ò™ÑÉa(ù¹³¤zœå8‹ÿ”˜SpíHẇÃýÒq¡¸ŠAœ£J°‰ ã‹n®†m¹‡¥#Æ©QÉCVÛMFòÚ¨ËK~ëhD$ ŒáêÀã¿ø>£=Ñlî%9„Ê˃>H nÐõ÷¡Ÿ£ùNmôQÍÝ‹]Íb<+4jà'Û⬓˜ßqä×a[áÀ+Vr³ÉGè™Ã.-ø×YÖé†w¥V“5B̼m:k›ËG·wEo†bxóó Ððê™òpêÌW \Y±Ha.³uè|«…3²½b ]“ço×xÃ*ÝÑ RÒ ÔÈ|Û6âP3ÞÏ‹¾ sŽ Ô ®/Í€©÷wÄ—ÿúk,>Åÿo[`¨á‹”yÕ,>|º |˜â×pHNmVÍQÊzÓªk/ÎÓø.U!GŽ…ß(€¾ÃŠ'“ÐF²¢‚fÿ%§Ù%%°9RÃè :ù}ï!è,ÓñmÜú? ?ßiP ¡‚\0T¦Ÿàï¨öU–®S‹­bà‡ž ‰QD·Þ`ågYµúÚö¯ÛW5TS%Ưµz> V¹)0KØrýÍ\ètw™©ØwÀ[ÁÒ\êoN‘6Íà€R¿åܵV5ܲbW±¤[ìßbƒ1÷üzÁ©c}jçâܿť|×o9¹Eÿ—Á`U..¡aë^ÃjvY¿8§G®à}îéÄøÔÇ/í(pª³. ÎÔ’dvf”µÈ0c¾~8ì…ópQ¥lΔ!ªà˜Ø?1vuÐÆ?éˆêï8W%‚¡:kgräöþ)Óa¸„ߟuun™¯ßÆ(»Û«™›qÿÒœ2í|ÇYíüu$4:8g- õ¦†† 'BAzë^ÞÓ¯®ÈZ?uîÝ‚›²_ÜØB¯µ3+ÁøýbÔaèÑ{Eã3n"U7mtáÑlúÎý±þ-ÛÐÆ­ðܖʰ<ÚøáÇ„й$ZKº ‡-ž`“¡+‡$ÆYlg¶ô0.ÄìŸ1•DaQâDœ½½/9eÎ﯒ë÷Û…}‡_ûyœ&cì¼8ò®ÝÖmVù œaàV*¤¬ÎÜ=XYŽMÙŠ‰ Â”õí¡W²Z÷ÅÁÍcWߎ*á0L-ÚE0WÉj×Ãѳ´âì‰D9EŸÎîáÞ7M…e$Ý»Ä2nþ6âåæIÒë–ê~‡ú¹bªGøH'x=y ¾h‡«?Œ¡Œj`iÌä„¥öÁm'Ü@î›g!÷5üf›úì‹(9S´ÑtËO£dôøÀ‘ÚÕðu)]Æ–>óŒË2¾"É!¿.Çåot(À¤q#Ù¢Û}CñIÀƒº­w ^‘¶ñE–fóÃÍðùvH#þ.´”Ÿ “¬7.Åá(\½nçØzáƒÜ•ý{S€X•H7?o.±šé®ÛØ.Fd¨Û+`öÇméœÊ!Du·Þž+ŽXnÝZ=S80»"ú¢©Ñ¤Ç~JTy‘‰æ'«ÎâC.[Ε¬ã4AV “Ó¾°˜t<¢yÚÅë9º(½]ÅýíÈ œ`ï^à˃rÁºÉÕOöb½W ÛÖäÁ³ïyÙ—!ã08(Ä ½%“ó½øËЏ·Ú4-׫˦VŸ\YŒ?«øNúäÁâÀÚÁC”Qæý zörLí®Sz¸SW‰­åªŸ`z²¢‘NV‹ß,KŽ>ƒ¶á;½q‘×…vdßÚÀtèD3jÖ3•E‘ñ_'['Þy Áe³C Ô«xŠÔ›§D¤q"B£˜&]‡Õ©Ê$Ã@ Y°³4À†‡æp°‹¡Ÿ$$ðRâ sö° °+ÐÀ’þM T|oDdPMMšÎ]#Éó¢ Øþ0†®Ù{X×ÓÂãíúˆë«}=pÎïy@aùõÀ¿žÆV*?ù‡ÝÖ>érˆ-MÓIå¸L¡díJSQòôö*v¤æs?A‹3äWs·Ð}­»~"ÈSáêÃUàîu4ðå+~ýóï]üßô»IŠùïümÿ<·rÁˆÑ%uxÿ¹9|ùÎ §Ÿð±ä>Vê ܱî›vÁÈ¡Þñ÷lŸ»«zÐ×P!8U޳Wý.ÝÙ¾à¢ý¸zp—¸ú |ù„‘PáÇþyþwý0Ücyv¡5VøAIv ¬ÊÿD ëöƒ£ ª7¹­’»¬ }^a²²/bË/¹äte/;W ="yÙ9šÔU|e·R* ¿dÛø«“*•le‰<¹éT²”µ†Í@1"ù=«>LQ8ÒŠÅ_§µÜsPÚ)$‹ Hgk«ûä¶®Ýù^e†CAÈ‘ý¢ñ.Ï®rY>'‘oŠg)Å™[ˆZè:j‹²¶)ò_É Š’›€·É…z@  û±Í8ú«Üôy*S0Q’Ÿ¡‡?± Yæ×AZdÖ AC!,«þÄa7i|­â¿h ¨|€ŸYyqÙÑuæ¤Çv’¹§,9ß/èMŠ…Þ‚2'F£;Þ¼Ê3ßñ ÐÝb–Hñ÷æõ Ð$½%zw­« ?­L |/›HÄ%WF\‡<µÅ!„¶è^fòT b1E>1ß[ @ø¦ì€`ä«/Z ¦í®”˹*êñ¨¥*ï–30½¿8½.™º ‘AxþÅyÕRvÉþn98xUTYU‹¥ŠA¼DÎ(HÛ·üÅymèß^(ÝA”Ô¿Ü絜ºÔõò/†…V„¥®@Úìü£ÛÃbu8dMå@¿O0 0àùÌvh•G˜v¨ƒô·´ô…EÐÉmÆÎl^ŽÎFeQm÷ºî¡@Pê@Ó’ Jdý”HËtñ/¤â Y¹$¤&E¾kMýVRGLω½§Á®ë5õÄûÕäI$%´ò÷—~d;},¸ݽ$hziDЧD“¢™>¥„§±‘¹Út×°ïB|JþyÏ¡kýü2™ÉßOù+#Ÿ•õ«ÜšÌù}ss.߸¶mù‰ ÛRl%Bù¿i¡tG3å`j×(p6aw1RG–eá©:$ßd½¯¤ð_‡Óeħ4J›t‘Û»W޼D8ƒy¥OžHz²ÔĹ„ø¸Z4¸ö‚ò‚ëó9& ÉÐ Wf~²*ì ):·áª&¥5¡ñ@Â=¶ŒºèiÜú¨ð} ¶4 Œ>6l9» ³C}ÒûÊ9é–Ïu‰GrÐ> .šÝÒÜ%Ø$œ¢@Î]L·5ä“'mÕHF+@‰É¤¸¡V&W0$MÞqþÇ“r ±;™laàÍ\\ANûY³ÝXËGšEiÁX‡ÝŽ\0\`/Ãë /·¿޵{:à·/ˆ…;óžäÅ¡^u‰ñ39ý’Æ—òà¼Á0ÔËâÝ[½H/:–Ôž¯a°Æ’¶¹T ó¥™ç¯mÞÄ9ª±&ò›­ÔAúô‹Ôž–m¯‘ÂSŸÅH[ž¯É×O?é‰Ë™²‘Æ:oÍgõ¼aÓmIá7I_ál¥h¼XK|r§¸6”s.{'±×ÈdæE)3‡|œ½•ÈŸŸHͪqIVСŸa¼$¸÷Oåf›Î'M˜ijÓKê\> ÁÈ-äICÞì¿!¥.Îï¿ä–5ÿe’ÀM”˜°þÿpÚ*`k(ÙŸ#ÄSz\å[stFétUœ–ñ–oUQ‚?2úõa‡ç‡3–³†v°Ó~øë gÿR»rZ“Ÿ ˜yÙñ¦‡3-{_¿MRúò©›sÿÚçñƒ:nåóH°(äŸg²×&I%§à2o‘)Ä#"óˆ+ùŒ;è®Oâ¬Ó‘BÚâ`€'çî3‚ŸòåzPpúÁwqÄàSƒd <0öð⺻,£Ž‹³UÂÙ9å•e½è_N×É×>%ŒÁG 8‰¡MÙ¿)%oÁÛMîRu/ŒK¥ïà.'Uköw*º¸àÏkÚ²Ô³Sc%µmQªÆòJuPpûaA§sòܲšþ,}ðCÏf…êÃIÕ)GÊr@óÙ#[~›/Fu,yÁ_…Kówœ«RQ ͻ݋3³wÚ‹£NÁØÄ­µ'Çî‘êò^çVì=æ* l¥Ò>Ë}°xRû¸H­ÅO\"Y¼CgäZLÎþ¥ ú?q8¤§ŸÓ¢9ÖçŠâ¥ÂÖ—û#÷-Ù‰DvÕ–§žhËÑ9å¡é’/–ÍñžÚ+³›ôóöæÜÃ8íhñŒôø&C‘ßq®Jݘ¹¯v/Ž}°žJÚ—k¿9¬ßí†bó‰ói¿—ðöŸª¡jòõD¶ä¬`ôù*ÚÇ“sÖÙkÀ go%NLûógm)Díãµû¯<€ík"Ã\’÷-ö½ím—å&g„®4•Õ¥²#8ÀPÀ» )BÊQžÎ\©»ÙFf'on¤úP@Ó.2ýp”–4 i8Ûæí¯,,9[¾?œ"74µSòæ+㩳ɯv‹25‹G5XzCF}œ"”víþm…¨|jçæÜ?Uˆ÷;NÎįc!gP‚âþçK®Ï»YJ^ê­õ®)hâS¿´ã¶‹ÜgÚhËŠìÍS€¨|¬öÚYÆpEWVè†*îÄ7¾‰ªÞí{ä g¼y\1 ª„mœ@m_¶Îvgºàðn6ÏFº…1‹ °tdž=äIzÑòàr–È»Ä4œ mڵÙWF¿œnª}Ô«±lÇÝ!·²%aÔ°wEç¹ÂSnÊ'Kòäkia•Ƭ…+n—Ušhzá“-[¥½ŽËyè²Â;ââ8™±†9¨ûbþæ´él› ]Ð^¾áܵ0ñ¿Û $,g&»ÕÎŒÒÈ2‰u†žb Ûpô‹| \?Á1óïÁ¾8÷„(XhËyj%çý{Ût}ªÄNÌã3g9ˆdK‘P>s>m÷–P(˜M©T” àÅQ?8æÄ(ÆÍ#o! CQYÆNI‘¥ÚJ’1¾µx"=ô¾ð¿.Ž—N¤„.ÑŠq!ÑÛå9Ý“]+Zó‹ óÜ3FÁTݽT&Ó‚3²Yú.Qœ`Œ€4A[ ×ß«1gØÈ1œc e‘{䋬:ÇÅQ¦áŸj@©tš$•q²ŽT'T£Û"ËiWéo„¿’-ÔßÇp†„oÕ7=‘ce˜ ?+%i1p­À£tÙRR¢HaʤteÒ³wãE 4ËAw‰¾"«“<Î^t·ÉñáÌ€´B]@Òž¨‚ájÎlT¢†bÿ[ ÈŠm•#½±@°º2¬+yN@Zõìä9¤×ÉÆ“…*ÅØö.hÛŽ‚š.¨€Sr¤.dá‹iQ™â˜Ò™¿Jè¼­ÁX9èaH³‹3²¡Cxá=–2—< µ”¼@¨hȧ6"‚Yß1cm b¬¯F·xdŠ—i]×ЭlΚì2¼°K{¦:~"6¿í{–ŸÍ"гº^›E¸g»¿KLOc{Miv"‡ @ÍœyÊwš‘Ú()`±À'áX6]a ¼qÈêJ¨ŽÎ>¨f;RUazI ?‚ÈP;¸8ªù–Tl¯öó«,3@YS ÉžiùÖœ‘Ê á“¥­êëYOC^q‰#‡=¢d,ð%l¦³ö>%v¬‚HhyÓ-œ9ÝYeF’'‹–«bßû ØŽ×õ$k±ôÔ–•K ð ᕽ ³9Þ½”Ùì]Âj<]¶·ÇƘpèñÖð.#â@mΣEŒöM×ßus²¸Ð¦r^eÅ´¢ÕןA£=¡³@Nq“ÍËß½$¯”ÀJðAußt@åw‰îEË%È6â¢=‡ÜªfÁ|a—“ª8*¹‡îâØÍ Т¦[d«êb÷J­y“Å'»N+%ßú†£ÄX:¾öÕ\®Î‡í¯ø,ÛÍt ÐÏáT[D/ŸJM—wœ^;Ð309¶þÇá§c£Tr(؉¹‚*Õ¸Q%’É ­Ã2M'ßó‚/F·«È››ÜÂÄ £PQ¬µ\HSeD‚¾‡ãtz³: \Z–EF»rÙ%[D·ÂT ™Ö–ó ²¯æÈo_"ÁFHDb5|—!ÒV¬Œn4}Ƙ>-€&AUTmyΆ\5Ê¥ÎÛ˜m£™"…Œ^çéE×H÷pšw²Røu#rueh—ÂZ)Io.´¼X_%;(“M¨àćc0¹C Êâ„+ Œí¦C˜¤ò”©Ž¾€ùZÚúÊèç q}¡øÍ8Ñë (,Vò zÓJ«ßšP‡q ‰^ÎЖ"bÀŒuçje܉(F nÓXv7íÜ«/Fòâè!SÆô†U~É1.‰pÜiêƒb¦<ÍêÐtVpÓú\Ð]bÅï Ãÿ¢î‘£ƒól-ûÄË.^V³|Ö•5¨DǼÈ,e…1<³XŒôež}ÞÒÄ:Û‰·nNIÿX 1WŠŠ-,­nôm‡ )Êùˆ€Û®Û :€6ŒÄ‹päGØ ÂŒ¨ ’Ïr&² ÈëaË"R!6ýŸÜyU0°zпŒy’_0êM·(´«e¸hÛ:À„%¯Xµ&T¨ ¦~ÑW¦§›SºñRvòl#¿1º1¥W@ õtzŒY} ï5ÒJ\Ž“º*Ìn¨üPw²ˆ”ékdOE$€ý¼À޶#ï^¯†Äø{5(W•Aࢅòdª§Ä•PvɇnÅN·/Ζb¿Ú?Ð?³!³†Ò)¶€Ò©N<Ñ# ®@´”~ Ɔðºªá¼³{U|5"ø P-%¤·×m¯{6üŘ.Êg§4“BЈZZOÕ ƒóÚÏß“^jÉ­©G‡èÀ»9¯Õ(ÞZ@,—ê“V+8u£~ÕiÚy–t"#ˆc»àù­¬ M'¨a/ÓvV‰­Ñ’/Õã¬Ä0( ž‰Œ_ %Q¬y!‘Õî¼ö@‘ÃãÞ$¶y<%š]xÐ;Í@ìÚ »·ú+nx6'õéùWJQ’0&׈{(éª?j\»Džɵš³"j[„pP:êzº8'„ðˆ.¡»ù“ 3W #è !ñ¤usÁÊÝ£U·W*!uB­£ëÖë{ð8¨W~ÿ¹ÅðNzÓ5ð_†eLž‘À6´N½„q“·'@Ec8oPCÍât¦Rƒø‡W'Ö´`}º¹Ÿ)Ýù÷´ä{l}‘±gC+²³0)9•jà•‹ÆÊk0—àN°.·é…:ŠO„ÕÕ¿GŸ0dL&Ó§l†Qf9ÂDjÕù'LÒÎ~¨Å)Eª.?g(¦aK×HËbÂ4Ùb0uƒ%^döuîbGR LÕ©éìí'¦Uo:@™ÄYWúL=L¾c¸ŽNýtµ*x¿nZhyËcm¿ÖõÞæìæóB°9[©tÆõén’(™Äñ Óu`4û éŒÎޏXá×q]l×´ EÈŸ[𵌕³ ª·æFŒÉjÆs¢@EŠêÔrH+äœ1œCs¥-’Îè˜ú{h–¦%E™(våoÉ‚ÇôÕˆ(– MlF&i 6b‰ô—>£Õ J-ÇiM´W ɵEǹåC´¶™i„'Usä‚ô¡ôÐ;oNÍÝ•œ±Û¾+£ÙëS§–sy²”K\‘ „¸[ŸÄš6·ŸìF¡=œ"ÝÃ’‰Îñ,l?^´¶cVn«ÀˆÜ)aSG½®{ÑÇ^#»Ê…«Çyöñ‰˜“Kvš×viÅgÀ^±¡vd—i`(Ö¬ùÊfÅù(‡°¬=pÙ g„ËvÑ(ÅbG^œé%pçv’ AÖê$i-Ü0hD:~W·{”:]ÊMëÃ5Rwqý¤|!½,×zµåHƒ­ÜFCÉÛŠTn³XÚãì¬7Íëe2_™Ü„à“™Z x}šî_ߨˆ/ïB«Œ†Y ~4"Ú38R(þ.bQ^Å Üe:ö8Ÿ¹÷ììeRÞ`L<ê$E‰ h[ˆÅg .•žd¿šx¹osþüÈSj<©Þvç|µÉ¤¤Ì[ÞϧÚô{±¢Á¶q;cÌÁ%_:ЭBMès3R¾&Á˜ÔS`Ï«û_Ư&cW5”+]±;ø€sŸ.ðÕ§5¨¦â)—«JoãyŠ%ÀÊE-Éí¿Û°û·õ½ú‚R±ra<`¸*£,€ÜQ\Äw­ÜÂö|ÞÓ`¸µÄèÎå yô:E³G@ Dì+60³ƒð ¼p]pÈ Ú88i7•½rÈùÆ*;,w¼}Vüù±–óædJÜ…E†*y&Ý„O!ù:4'®“ÛÙÚ‘ø‡èš¿›‡¿×ÞÔµðga5Õñi¦“8ogýKá&xäÒs,ÔÉÙïKsâ¶ÏKUKS¨ñr§÷diEVOšcÿp¨ÚG D$QÆÑiMhåj[\-¿v¤³Ôðø˜DH.©e0ˆÁë~Y{$ ô}(GÀæØ#ãÊ-æ0°Ñò”=Oä¸ ä†Óåéæ~q~¿8³{»=µœ±ñÅZÙÃÉÝ^·CO£:œÛLù–YæÜrÃmEubÎÛ «¬ä´°|®U=ïœL™@5Ùc,Fhàò˜Mîø0Æ ÎêYÔuXÌ”‰Rª•‚Žnå›V'AÖ<%ZqŸ ZH10¢‚C'š¼ßÄÀG·çûïrNîÍÁysú ê§VÍQÒ'{ ‹VxÇ{o!Ë®mØ ®7‡]¦‡i‡ÖÞ,¨±÷4í@œ›S³Q$œ’ï '{¤íɈîY)7ŒH,X4‘°éb]¡›ýåMØ%ø<(5¡àkø@ôû&5´rx@‡¡Eé¤L‘¦LÖq/œ“‹|Õj  i.‰ÄÎ˪ '®z «„ÂB†ò‹TÓ¹x §è®Í‰q´ÀÊÿ‰3«o hܧMâK΀ʠFŒ¤&xNk#õuºÒME¹Ù §i>qXó÷°ï*_e¡ôœ+ÉÛuÎU åÜ¥© t¥±¥iÃ×¾,@çfÞ™ÊJ XͲAN¾Ü9 Û÷åóp.ºKžJU¹š©îä?u è¢)^­¼KTë ¶“…—mD Au‘ë4‘p„4ÒZ”ðæ€e'´?ŒBòÛºï£^ ÿ¨Û(-ж’Ú° 6‘ÐL/ù¢·>{ûü}8uø´­«Åà¾8‚êÛ¢âH1¥ Ðx9CgÇ™e †E>•}ÛíX㥴¼[Ù±+‘ž°Ý©÷‹¦<`НÅ)©ߋq|PFí˰jX–é. M&;{9ezJ“º˜½ *ûèåðN2VP÷šiÅ`fYþ³ˆâIÏV’*ûµò”§~5Ò¯X•Ã)‰{BÑ ý͸7ÔUå+ƒgàØ×Ø+Ãm~‚>œÔül¬Ó˜?ßqîZ×&|Zþ²á%x1(Ó)ÔŽ½O¿V­D:ì˜hE©Júd73 Û˜wš€éê•ú¼ºªu6œ‚\wœªä“ô¬êzn¸›ì¬öi—®WÓË?¨óè'„™Öw|€p˺hjDz»Äð‡®;’~Ãû—·UnîUš¸t¯”îE(NJá[³5‘BiQ}´îÈÃFòuáû-a-÷YÌWƒšÚiHÂ匼€˜ 6ú¢S¨oO@î¦u+ÔšD‰ö‡S†ßýUÞzå[ÎSk [Á’R¨ÄÃq:g ¡—X7¬Õ°¹næíhAˆ&-æ€LÔ,–f4¦پhͪSh<%¬=† c•+ h…ZK­›# ¤Z½K3ŽV•6A°üÛe;£´M-Z½þM_Z¨N‡.v̪ìö¾Íi‚K‘SX¾QÚ1µxV½ ‚ñ emÎtüŒöŹgD"¢Ëyjùòj8lÖò©Òt&ÑOœñáV²“¿Ÿ¶e~âÁý¿9~ÈŒí ŸŠ¡ê´;H„Ά”‚Wö–Èm$@±½ˆæÒÿŒíèÈ*[˜tÈàg!8P¶`ÓÙ6µÄÐ:£AãbR¡Ëí¢b^#•ÙLZ,°8WÜö&©0}]½ ,ÇAwÑØE:ù¢WLŠèa†T9; P ãlÃÛ:©K¨bgJ²ßŠ”WÎT´”šhüYùj·2{⼻iaE>»¼23[¡€oÎR¾¼3²éà ËeP”ë§eÜÅ>¥bÈ3Ó5¢v *e!)ÙJÔ™ít8 PýýâÔm%ꔪ0˹kMÊK=Z~qªoª%$ŠêjŸ8vЇ#DžvCÂöîò_Œû—þõ³b3s²,áwU&Áøý0ðO’̾ë :¼9Xèö'Ž(~ÊðTÁ—§âÒ8Ôè^}k E ýÊ’Û‡^Ú¨‹« P€÷ÉÉp±ˆ@ -À:¶Tƒyúˆ9'»  ™Ô°ãM˜! 5x'ô-—÷œ÷QezJ4áÛŠn¢åÔ!ÚhÏÊ?ÛÍ!-@„7fPÝϼñÇ<7*ÑrìÛɱ âz€|µ­¸—Ø‘‘Œ‹Â1£ Cž#yÚ_lË¿|š>{_fŠ><®)7‡œ ûAE½>1œe(ƒ?ƒ#KB0E}X×|(»öFÜiÂé£ôédÏΠ-ž/ÖX‰ËÃÓ¤±,ù¦5ºç$xÈ2 gØ8ì¶æ_\®P¦×k‚BÉ@–íùĆ€ÒܸÓÉé2÷M%Œ93ì¹Ñɶêq(±F¤ÔËÃë¡YÃB4÷ÿûï¢l0³i±gý͹v’k|¦Ú%6¹Á…_Âìá”m³Ñ\{þ–sÕº7ÞÝò—-®Nà·7“lN;; ìÅQ¬,Îݹâ †³ ½8Ÿ[QÃJ¡”•µ`\¨›óûÅÁ¨ª–S3xÍÔZ¿ŒHuª¥-WUàotúEŒ®ÔŸYñŽTð­9£%"4@]Z P–-0q—»…8rHü•Ξ‘à‘¼p8Ò5f¼~HS‚ÊV€:E`5–³pU¥'´¬¨¥³'†ðÏιðm¶½´ÄBèi‚üÇ„§íõ¢W`ïÞœ©8¨æn±>œ9e£ùÆD†¿€Þ6JM$Ž?È/4w¬nÜz€©ÍνuÑÔ°*áU¢ ‚rKa­n&YCeÕbTQ¼N¾ {/¤gR1û­rîÒ €œ³róµRSÝ‚ŽåÀ¼¼æ:K¬åæpü-å!dx"m ¨8)Ð;Ë€-Æw2RöXƒòÉ80¹# ¸Î80åìŽo•fd•àÓŒK§'£†FÀ™N¹»ì²o:–0pw‰± ‡“d5ÝyNwÓøÏ({·¾,yìw •AOúRI¿8Y¯R(3T=¾aÉÈ•[äè‡3Œ8Ym²Cî2NZå²®çf `*XÅžq¬ÑœÕ+ª8t[ÆI¨ ±€>P¼šŒØ¼¯,RjæÕ›QaOx“E"7?ÀÐØ]õSgƒz%zIj*ôzÊÕ.3›ÝCòdz+e©/rµNÿ×KL™óû/Á¥»‘ Úðø«3œ”…ýáü~qz¾8W­¾lŽ{8¶F¼9[wÑ•í0,ºóm q%g×¹VWnáô]Ü ,exlu;¯ìTbû½b$©´ðd¢Íé,¡øéC.wœ'ƒ`¶ËE>z]¸ ((´»½KH.ðìÉÔ|¾®¸œO‰áNuå<´UœÐÚ5«”5”)ùÐ=J(nv‘ð\^=°õW Èáœ?W‡ôv‡9zÈZ¾o‹›vV ™¯¢øÿW‰ÈjJ •a»\krôðWsÇrèHv[+ÂX×\Êm­ïäâYgØÊzØÃËÅ·ä%'¦áaH^»ÙÅ?é¼€z³l.÷×f†‡ãÌ‘¿=›hp¿á<[êªõ§8õ°fÀ~l@•êùópì¡­9èõoÎ]ëÚˆOË_6½ ݪ7—óäUG/9ðxÓ¡ïÔ‚NÓþæ|nÇ9ø’§Zð‹n;•È!,,ÙE˜ò¬&á,2Y+åvʾK,A–Mg!ey(X#ûjKp´j¡ÛܹªCø:Ø!›%òY'yÔ-â”T;E°ò"î@ùÉ“¤ÂRˆÈ4}Ú\`%ìvÓÔpìÝS¢yAZh‘˜=­ÄÞ•½¢=ÒÅ¢‚œÎþšŠýdAå-²­&~bçòÕ“w)fs8ûüpŸl¼îàçuú0”Y¦ƒÙ†@¹é9­}8i8ËÂUp™’d&xqØSz°¯êÈóo8¯Zͱ¯–/Î Äš‡³t‡×zæg›¡¾ìd ÛÂw£8õΞ¦éegóÄ–qÓZ ‘Òú.aõ14"Y©ê§i=Ü´œzÔà­^Ã×B΢j‹0 £‚2Lj£µ“¾':g¯ðÕ^Y³+yfsªö@¶Óè–¨Ô®Q’æ]ÏýpžÑÌŠÆ{ ¸Ïœ¾Æòù›óTŠ‘µ{sö²ëæ]‹^*ËÝ‹3­øYÚÍùÍù²óÿ蟚n-ï³¶ñ5VSDmU DÌÍH^@Õ™¾¾a\U”~Þ­¾8Ó £ʱ›3ÇÜœ™®¼ ÃÆîVØ»¿sîßúW@‡ß8a+!å\6Œ)¸ÉÒÛíq’üÒ€{EZc',JG%Äèv¡O) ¡2×,æòõª"9í;o-cš~,OpͲ¼•«?bnƒÏÔbܛϠZSw£ ÈÁ“@ZÙZ+ÄEœ¹æÈsEÐ@7ªT™áú¥k;Ž )]DIUBöç‡Þ¾„«bÄ›á Šƒ!Ñ¡$9ʨùxEÛý)•„ó°áùbÂf.ë=ZGƒ-@†b×Q.RƒÈÕigsJñØÀ6(ñdSß·P¤º¾khS}8f÷ÒY¯$Ä£.AÞJ/ïÓP?-ÛB[fŒÆµMÞÎyÚå©){×¼Z®ŽáOÅYG2Q&=’ÆšÑÓ|+‹‡^Ér:ßΊUŠýƒÏ«ßÐDø®ý´\Uõ%ìÔ#£èB6õÄd¢ç‰ªGlµ^ª4CROs5ØyCûξ•œ"Ê^"‡ö²œâgÙû4 b«ôÜ ]D"\º/€Q¢Ãªñ,TJzûçP2¿ìRºÕ o’{½…ì4гˆ>îöûÝzššÙ!åO¿º­×!à\õEgQ©†æ,ˆH§ŒŽëÀìpÁ¯U®4„]®K-~ê¨á„²¾P9$8{—•§iA]ØÅ£Erp¶:ï2!<(µö˜6lË Ó]X¤¢â:ê´ÑrNž®ô•zÆà‚¿uA®WŸ}Q:s$©TƒéŠˆYéêÂÌ’Žf¡[Í×üù24?£š=Í¢çŹç³PñþD)CH\ÇòCPN-ªÁã„›¨‹ÜB{.a!ÊaÙéµÿ9mkXYzE•‘§ž Rr|«à[ ¼q’xXŽx{O­/[iv‰(üÌñ@bï«õp®2·}õÃÓF-©É9PeÚ×RœJ‡µ+ 3ïôªsJ*¨?ŠôÈjÆ“WGâ“/ø›ËýžÒ"¨G!.ÎójFRáØ›K €¼_rgq„AÕl—Av2-©lïõa]z¼è÷ Gw[Wë)R×^ˆWyÛ{¸ŸRʶ5ÐY²~Ó½£”/^x² SµfÐz‰œËCþô*ùxÆ/üZ/%Ëá·ÈÕËÊ¿Pѿ˘¸„~CZñ=0AÜÆ p' 8K+¬ì?c_+Ö)t±¾¬a)¾11ËŠÄâ’2 RË ªh]Iê£í§¨µX¦q,oEžR •QØ10º¶0%h Á{ŒÅ¸G •spNµå·BvѫԲVF޽Ëá+C¿'> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:10:09+10:00 2013-08-12T12:10:09+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/relative_noncentral.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000022755 00000 n 0000024441 00000 n 0000022696 00000 n 0000022555 00000 n 0000000015 00000 n 0000022534 00000 n 0000022819 00000 n 0000022860 00000 n 0000022889 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<1FADBCD35EEA4C119A2A87A92B575E61><1FADBCD35EEA4C119A2A87A92B575E61>] >> startxref 24691 %%EOF opengv/doc/addons/images/multi_viewpoint.dia0000664016516101651610000000713713344612246020216 0ustar dimadima‹í]Ksã6¾Ï¯P)‡\èÆ3Š'UIUv©Ý­Möì¢%Z憖\=3Îaû¢AÉ™´=A›<53%BÔ×_7Æ?~¹,&Ÿ²r“¯W'Sž°é$[Í׋|µ<™þç÷_¾3Ó?~øa‘§ß»¿Ë2½œ¸O¬6ôêdzQUWßþü9)n6iµ.“"¿N6ÙñÿÒ¢H]£ãéÇ“Éýi•Ò{ÛwÓª*ó³ë*›¬ÒËìdz–ÎÿX–ëëÕbZ·Ú¶›¯‹u9ù”'ÓoÎýÏôxÛÍñƒ~žèû*]fge–þÑÞ5s?Övéú*+÷»½¼Zorפº¹zÔ¤¥ú÷^›m«k´Z~üæ×¬ª²ò›zXÛ7ïúkl« ê2-—ùê±,÷|Šúa@"ÑÒâF"»çòõâΆW +®V\¾9½Z—U™æÕc‘gëu‘¥«ZjU^gÝålæiá öÔ´x÷ÞÏóªZ?3þ󴨼dõÛ·÷µÚ»,óÅÓÊû EK/ŸóEuqú%Ðãª{¿ Ôû§|“ŸYÓèóUÕ[÷7ýt¿ÿíx¿ûøh¨{k5 “ÉL~½‰X^ç‹ló ̶iéébÛìø¹§¾ß~kÏ`{Ez“•Ûîº3Õ“í¼eœI:¯òO»W÷žÉúì¿Ù¼ÚNö·*]-Òr1ùnòk¾rŸºuDœ’/N¦ÿdŸÖþü\oŽ=®«õ-¦@%h€N¡Ùy¤MÌÙÙ¾”ÒM$]-‹ìNWš$1C™hÆÕòm7Éóõjuš­~Fæù¸©˜B40.ì6°ÕõåüjÊm(÷ËÁøV Cæ£èþŸyÄQÃÿ;¼÷&ØÐHQ#7œ7i7¹Ó´,ןÛ p`×§E¶ZV¿¿Ýº3¿‡Šðûô‡HèiS‰õŠ”JÍI(/†$qnE"%“Þ<1@Œ¦i’qH´è͆pËì¨8ïVqxoŠ#Ãj2µ%$™Á)´ÂüÿC)|ÒÈøVäCEey·Ê}(‹]‡èEè/·<¡Õ D¢{_/C`iœgƒ©‰Ü´óN\¸UÇÃì¸ÆìlJ¢ŽêùÔ³ýhÎaëöM óæBÖk·@÷QÚøJáaCDçÙàÞ®Ù¨šQ5;«¦èÅr>j‚­Ó5˜$ÃÉ5s 6(àjÃÙ4ÍFÃÉ4¥NéDÊ®=ªç_J=ϾT÷Ô“ïÔóàý …ÙÇ$hªâNàÓZYRºfãVô<ž9n±×¦íô?Ÿö ÝÞq¶/-'Ùž8þÑv–h½ªš$Ñû“óô2/nÜ€ÒÕf:ñQsÏÃõGÿžŸ²*Ÿ§÷™åëGp‘åË‹Æ1Ü;Ÿã0Zk+A2‚&ó!_ Â.’ö©«õìä}úê"(-òåê2kþ6ï¨ì¥R¼|B|òCjgU†NÕà2QµÑ‰îœªÿ2oa+H%FÎh§Á µ0Bº‰„˜ÚPIiŒ¤tpf 7Ûµ4† •sŸ (ÈI¢À9z™rNÒŸ‘“BsR#‘L?é!8ù鈃¤l¥àG@D1b‰aDp"ÚG_d¡·ÌBm‘Ý^’Ô7uÈ“]«A¢µ¬w%™1uªšð‹7i̹jólh ‰1€40 ÿR¡Ý“=cÔ8¨¬‡‘äÈΓ—®‰H$Xû!Bû¸1ƒ1x"óa]‘_Ê,û-+óó[Äìü‘Ÿ××ež•C¬Š´Ñ~Ud¬B¡pFš‘]’º$ÐG‰Ã…¯¡C.P%ZE’”Bé³:Eì$0üqÖæy64UuSÀÄv~$1Éñí§j@/µkŒ­+Èp©Âhâšj(ÊÍ^{¤±^²‘0ÀaðÆy6Vh%ëv=S5¢z:õÄ>ŒC_rÉ0´~švh7u­uý4¥ ‘ÎØé!Œ[ã<šjçý9+L‡qÔÛ+ õsDú)zq>A ¡Ÿ‚ëZ?ëÊoš±ð„I°CøžMÓlh* LG (µŒêÕ³{ÌêàLG!)hì½>»6¼•dtðŸ *²[û›B23ãf~+càj„;úppÚ#R]në£4L06pUK‚„ÄŇTi0f?Frjc$§1’ÓÁéh¶A5ùÃFÕw’møZÙ °^²…çÓ ƒ“S#9‘œLo[~n±˜œv’4UdÀÙ=ÉÂHS#cjd+#91ÁöBNª¾ˆ† –œ´Ø†„QàLˆô>¼ÒCÄ„›æÙùpó£ŠÉ‘19ò šñàäHÁ&ëØRéo%9ÄJ§ôta„ð;§Jt­É4hŠä·“˜$Þ-iEdtKFè– ïã>Ÿ¨} 8dåLÐ'h8I¥¯Oi’H·~O“lgCS¬›º¡‰i’ï7Ï¡{T*Ð<øm­$I%–q=Cpn¶õÚ¤@ =Íólðÿ %Ô×Ê*ˆõºß¯ö`ŸÚØö¨„1õ]Ljd{4Řp+ù€ÚóœíÙ6ucÑö¼gí½ÜnÑNwü…j„[©xÏMÖ¶%Ê!n ·/Óž(IÃŒ †Q7ÐMÙË-shê»ÞÀ†¾eÎl-›V3·h1–òlm¢Ðˆ!n™kšgƒ_ÈmAÐÀ$訟Q?»ëg/·@Râ:iÔ¡o»ûñ¤žüý}uJ óhšeCSÒJ:7àVoJÇþQ;»ïšždæL…ªc*¬g{+I&(ÉŒÊKØm”%¦çÇ$³'À7LF˜d†'™9 i)#Y"lÐôü$ïÊSÐ é"/Y³˜žÉé 0Fr#9œdæüqpøøeä´“ çä^[JÏw’‘ÅôüHNO€1’ÓÉI°ÞRMd¢ƒo÷í$qcüvßîµÅ˜žÓóŸc$§æÁ‰~òà¯c¥AÓó%ÌG€¹î©I¿_ƒš’×4ËæK#­Ò40`6¦èÇý·l}¤ð)–pΓa½’Z’N´vN‰q+'í7DÝÚ} EŒ¿)úC¤è·"2º&oÎ5ù[¶¾Ìܧ探þ••çô›Ÿór^dMduxÆ$K€+Ú¥E¥!¬“ÂU-ˆk «­•åôÒˆ®æÉ=§ô9ªZäóª£e*²K甫¬ üü¼¤gÍŸp|÷£»^:ì…=¢©PÒ¼ßóìÔøvÆÙâΛ„ݸë'ý8}Nº‰8Ï‹"°ˆÍ…s†ÎÒùËr}½Zì‹9[¯‹,]Õ‚ªò: ç²GÞü=#ÖñùùÕéźÌÿtV9-žœÜyZl²Ä8¶¤`C0!›ë³ë>›v~HýÛƒÃëŒ:>NÕ>A¨ eFÚk/È- ù É(z©óñÚƒ>ž_´ÑD{íAö@ö°ÿkAŠ#îxMJvÿ×è­$&ë8&cþµF6b“ÐË#Œ6!Ú„h¢M躥ú¸¿g[TÚ/…'èh-U›¢"ÂÂ)?­¥Uühmë<Û›Tº4­}ûǃ„îS{€‡®Õ¶½½Í)‹ž •€/ë@ëm‰j<]ÖÁ ŒSYQV,ëðŽwTM‹ÍÁA…¶Ã®AjAιEKKé! tïâÛßO½v3õ÷ü2ÛLþ‘}žü{}™®î¶To3¾|‹ï~Z‹w¹­ÚË`»ªé‚þÄ]Õ ,e{Èû à`Yàú;A•¯{få–¦¬AÞ<µGSõ/à)f-Xi‘ÁéÀŒ<5Bž’¬->Í€V:l)‘$Z‹€¶TJ„)DºKw•ªwëPµ"32Õ™Š÷P¶ÁÙJí¯ø´Ú†-Û°“ÄÝÎéì³OO@ÁÒOD—jH—ª™‘©ÆÈT‡çü;<0ôE™¸•K'Ö’XbáŒ2¦œ&É’IŒ>Uô©^†ÌÈTcd*ì© WÂg¬[˜©jIΗ²hfN"èmá:ÙiŒ>Õ aª6dF¦#SžŠ.Ôè ÂH‡Å«¿$NÅÜ®­æÊxɆw•}ª÷§jCfdª12ÕÁIÒÄFš#S eª$ÚÊQš˜J ðHt.Ö.eƒèS §jCfdªqŸü–ª÷J)å&tXïJqåKJZë)‹ îåÊ1ŸüîãùÅSñTG<ÕOul_éMV~üP¿p—ezùñÃÿ7ͽg¢îopengv/doc/addons/images/noncentral.dia0000664016516101651610000000536013344612246017117 0ustar dimadima‹í]Koã8¾÷¯0<‡½xVŸãé`ìa€=Ìì9PbÅÑŽc²’îìaû’”“Nª;‘E!Î0@7`f±äúªXþåËÕjr[ÖÛj³þ8Ƨ“r}¾YTëåÇé¿ÿøõG3ýåÓ‡ŸUñ“û·¬‹«‰ûÆzë?}œ^6ÍõO''Ÿ?f«»mÑlj¶ªnض<ù_±Z'nÐÉôÓ‡Éäñ‹¢)ü³ÝÓ¢iêêì¦)'ëâªü8=+Îÿ\Ö››õbÚŽÚ;߬6õä¶X}œþpþ¦'»iNžÌ󹯋eyV—ÅŸÝSs÷gmŸ©¯ËzÚ«ëͶrCš»ëgC:æñÿ?³µuƒÖËO?üV6MYÿÐ.k÷ðë|±Åvj®ŠzY­ŸÓrïgÕ¾ d’¬ÿS`$qÔtÿ^^Oîl\r«qÉÕã’«¶§×›º©‹ªyNòl³Y•ź¥ÚÔ7e:ÛóbåDì[lAÿÙ/ª¦Ù|gýÅjûÚLj{-z—uµø6xŸŒè˜åsµh.O¿$z]íìw‰f¿­¶ÕÙªŒ­¾Z7ƒM7Ìôû¿NÐà_¿~ 4´³ušˆ…)e)_o"–7Õ¢Ü~GÌžŽé˜ér7ìä{o}ÜK_LûhÏ`«â®¬wÓÿý«©žì~àÆ™çMu{ÿéÑ;Ùœý§n6§Ÿ½®ë̓L‘eJ+;Í5쿉çz¤‹ÌÙÙ>•Ú1R¬—«rGI1Å5zJ\j1w”µPj†À˜ž”Ï7ëõi¹^ŽzñªÚ¡naÔû•¬o®Î¯÷×Còk&uŒžu½ù¼?qéÈí¬(8õéª\/›Ëç?æ½åLJ"hêC(´[¬ô Ü •N ˤVfŠTz.ÒS–’Óà‰òù|¨[G«ÃPcuÏ{ÄÔàA%á^|½å±Æè2v<ðà÷,Ïn¨[ϖ烇†„Q,bÚiò@)@GC+  Ôȉ2ݳicÅ ‘ÙÞ K‚œ•“€Ó§S4`çãj›o›bÃ&õNlo ¥ní7b.$ãŠh†œ 2b »a3²'Ì*ÖEÊRgg_pÊA g+µHV&F§±»]'Ú¹@FB¢7Q¤ÃvÆøŒÀÝöXÛ©ÿj¶3PØ6w«²Ÿ"#LäÿQ~i!vÈW‡"ßY!­´ò!B$Dþ%ÉŒRÖÛe ”­€žþfã_Ëw¢ü{cº’V!-údÜ^õKGõY‡®ÖfÝÄ(ùç“‹âªZݹëítP4}ûÕ–«Û²©Î‹Çºëõ+¸,«ået ÒB $­µ•èp#à0šOñUÂØ‡Ü¾†ìÌÛ?Ö’}«j¹¾*ã?éWµöR*ÑdËëPq–Ô­aiݤÞ•(ÆûÕ~çÞ׿ԔÀ”},Ì   ”•Dxûºé.ë¦Äº©S³n:BÝdÖMf§! J¿L7ÝSBÊ*lDh£ÎFª·¯›þ›uSjÝÔ%ŒY7½eÝÔͱ‡ê&/ÜyVn3£„IéÓaN¼!aÑÜÖ3 Bbâ`N'›Ï‡ºuZ”Æ/Œk¤œB|·Å+—~ù\™5­T‘¢”àQŒzô çzD laOŽž.>#èQLH²a(Êœ€¿è!Ðc¤“””Þº#âöUjFÌ ·Æ‡$GOUòäe_1;FãÖh µÉ˜y·˜ÁA¶kÂxõJ’ǽ¡=P„2-p¸Ï” fÔ›µ“‘¡œ)gmܪ´4˜ó⛽±ICØ3­„[m-¥u¥@:ßI1D¥±Ý úí™VÂ6-ÊfÔ•B!ý2­ÊE+œýÁ)ÙlBZ¡%¤ÝqZí¤žœ ä §fBï)Ð8:£|F†jFFû… ”Öd|f|öM‘ÀÁUe`™‘Fø¨RÊ¢²BÈHk9÷9:N°(siIN‘tÉbÎaöÔ>7Yif’ nRnv”C#eð¹­àž2).M.-ɺ©S³r:FåtpÝ›?¾¬Cˆ™;)Lé×ÜSr>=rsçÜsEž2Z) ×–dåÔ)ŒY9£r2Cd+Èk H»iòDœèq9 ˆGáËýÅ4g†?ý#ì—ž‰`ÖFGXéÔº ÑÖ€% û3¾·Œ£ÄA‹ •”oÜL Ò£¤O#|F«u¬0à& 僋ùàâ›l”3H6¦í©„”ºÍ†²VŠæ‚˜.Â)b9F—©(›‘ãsÄ$…uZ“³žýá9D8nA»=¼ÉÔ ?¸5svOɶᇠé)+cÅ-â|Fð)!Y?•Í5ï=C´¥ƒT!¡H|¼Ì*G5ùÓeÜg@¦ŽÐË*Îf|¨TÒ/LIžÁónë†èiJøˆ‘MÛkêž’ög‚Q{Óƒž²äuŽŸçøy§0æˆÕÆÏqˆ>x’lëLZžº;r „ÌW5œqZÓQ&®U®ŠÊÊ©S³r:Âp:ÑÈ¿`1±Ó®,Έ ÎQú˜šä=(Çð;¢|Fƒj¤!,TK•[·¿_¿ãð^zÀ,/*Zq›´—ÞŽ2ËIßESò”­6}»øå¢Âwåwt c6íÇhÚõ E ÞäHZTH’q0áx>ç2\i„$}ˆ‘Œ$3FH1Ægd¨dÀÉú…j49_–7ýñi†À§Þ…•i·ÞÀ­OC¡oÅí7\s"ë|Œ|vœÏh nÎ!0$S¿d|>í øl]Fߥ)1>íL0 $í\ŸÏic ÇÀgŒÏhh›H ¿Pc¹ÍøÌøì‹O¢ $˜vß—ô bÊr¿ÁDaÀ´ýXoãfÜó1ÌgŒÍÈHçùùÂëÐÉä:Ð\úx¡0¾w»OkQRÇIÀö 9:ÇV0cý ŠŠg±S#¿‹ÏÈP·0P"Ü£@ úøŸoŸ8>Á´bÛ÷š——“Î5 (8Î=aí/Ý•Ì=ž16#g9¤ÛØûJ6Á,WýÑIC Ó,òrK†ÒZONÂï\¥Ñ:ÀSï:²I/cŸÑ¡dÛúqk%e|f|öƧÄzÚÖ¨™Ôø$?HJ…KmkÑä(øŒòwˆ¡Rúø8ùE;½ |ÊAì§R%Àmj|rh··"¤UµÀö.ÓÞ÷'¾Î~Æøì8±áx$È#Üßf|¾|ªA¢Cºµ+Zê´=bj/ÑF©à~Zjí§5Ft(Æg¼¬R¡“ƒ§ÌøÌøì[3I—%¡`@^­N™´iÉg»æè/™•3àþ®´#è't>n©ä¯uYþ^ÖÕÅC½¤¹¯—üÇæ¦®ÊzŒjImt¨–4V‘Ð#´ŠŠa.•<Â#Z4ÈÝžÂ÷z·(Ÿ¼3ɸB¾;Å=YË ÁÑÑó¿M²fJ¯™â˜5Ó1j&;€fr>ùÄ.·Ú¦UN-%¿[ÒÒ«'É}4P1dŽA=eý4’~Š‹dVQG¨¢ÄáuxÜ÷Ž—ÊÉ´'Hï ùŒ»>Þ¢üuÀ>ÝßׇSAÝ^gõ4‚zêǤÚéqö5k§˜vj?¯Š»²þô¡ýàþ-ëâêÓ‡ÿ¨Ù^¨opengv/doc/addons/images/relative_central.dia0000664016516101651610000000703513344612246020300 0ustar dimadima‹í]KsÛF¾ûW°˜C.24Ó=Ï0²k“ªì%µ»•dÏ*ˆ„$l(RBV´‡ýí;= -‹ô0° ]ŽB žvÝÓÓÝóãÇ¿®–“OY±É׫“)OØt’­æëE¾º8™þû_Þ›éÇï~\äéîïE‘^MÜ¿XmèÝÉô²,¯8>¾½½M–w›´\É2¿I6ÙñÿÒå2=vO?¼›L¾`‘–)}¶ý4-Ë"?»)³É*½ÊN¦géüÏ‹b}³ZL««¶×Í×Ëu1ù”.O¦ßû×ôx;Ìñƒqû:½ÈΊ,ý³yhæ^Ö¶ú:+ö‡½º^orwIyw}pIÃ8ôß/®Ù^µq­.>|÷kV–Yñ]u[ÛïÇ«»ÙF ò*-.òÕ!–{>Ëêa@"ÑÒKq#‘ÆÝsy9ÜÙ°pËaáŠaáòÍéõº(‹4/!ÏÖëe–®*Ô²¸ÉÚãlæéÒ‰ØcÓâíG?ÏËrýÄýŸ§ËÍs&P}üYã^ª½E¾x\y\Ñ0Êm¾(/Oÿ ô¸ªÑïþ)ßägˬîîóUÙÛðwý ¿ÿíx¿ÿ祡­ÑD,L&3ùrqq“/²Íbö𚆑.·—?õÔ÷¯{>Ú3Øb™ÞeÅvøŸîMõdûog’ÎËüÓîÝÏd}öŸl^n'û÷l}•9Ôùäýä_YqN¿ù9/æK7À½O2ä‹“é?Ù÷?U7°ãă'w½þ,^‰­%Ü Ü(‡”Òsv¶R¸;OWËì3ê-¢œ¹÷Ö>½WÒ´DvO*>¡‹|^¶=[fW§óu±:ôPú~„Ê“ÙácÜs8ÂÞ¿4WÀ.³üâ²ÍËìé©qV½¸°ŒsÅ¡ñÒMq(÷l•.èO;ˆó|¹ ±¹\ßžÖøüO;3/~V›òn™íd«›«ís@§µ†õEÏo™_Ÿ^®‹ü¿ëU™.Üž§óbG˜e>²¹9#w0›¶~HÕ‡•èÅ$ð®&ËDY&ŽÀ$È™ hITH ˜™q•p%ý{m¤¯IèåF“MB4 Ñ$t7 ÐÙ$Ø-SG\'5„4 ITHÚh˜¹÷FI÷ž˜`Ä&¡GMB4 Ñ$D“Pk~w<ºH‹…³d•5v;Û•#Ý&Z‹f`dÇ.3GšNé…X˜i‰[Ò3yÂì]Óôuú-¦×ííH]7lF=Ám’O'ýuHôùä<½Ê—w'Ó?ò«l3ùGv;ùm}•®¦¯®'SæÛaüïZ/_jêËoçÀÔÉ2Yn£µ¶Æ*š‰n˜Eò%bÙía˜û™¬Ý(]æ««¬þëm ÖÇvê‚Ø/ÓOþ–šY!)Ñ9¤$ êyÂQ†tVwH@N*ƒ¢),D[äÈSo–§%3Õ‰Jvö¦œWõ%ú°Ê†ô¦î¸U’Ü)!+wŠK%_?Oñ×ÁS{4UýržbЂ•÷§3ÒÔiJuö§œWƒ[¯F± þÔ‰%Êfò§„BNÈJhýúy "O ÉS’‰ê5Õߊù<Ŷ<¥{Ø·-Ä‘sr*ì¾5pG´Mm¤9¾BŽöˆcÂA´ŒOÍ׫Õi¶Zøµšçá¥îÆ@‚¿1æ–8ín,-æ§ûÊQ›!~Ÿ|þ™ßŸ²ÓE¾qÏxþHô½[6£´Ú¡¡ã9–½†'âç-¿÷ÀŠò4-ŠõmóؼóاËluñø³’ÝAžü>ä î’éì.±ÄhÃ9¸"d|‡¤ÅPr—¸”ŠˆÁ´FÒ]úm29ùCPƒ† š¤3˜Ë´o¢ËÔ‚¬~uF¤Æg²]ÉÊyÎLJA‚5Æ„MÿV”G.g…*ý0°ÇÔ8ËÚdn-­õ¡1-—œN æ×û÷SWÑñ•üzpîÛq¢´9`úÝo&—Nøˆa,×¾Ô`rÿ[G˜‡õ{ƒö#âœGƹJ˜[x$nx%ãŠû]l÷?¯GÊéF-øôTÁmòÏBο’ó>„œ¶À¹HG6COY¹§qæxòó¨!ˆ¼v–µùvFXIùvVµ](¾I‡¯$ã0w^€äû®)¸c_„“GÅéR•X æµIø“!£ósZ´ÌM]-Å=>.êq1tÌ£I5±ÕLz±e¨ÃîY®½n"z‹s§œŽí-ˆ”³v–µ[ÖjåoŒ •3*g[å}('—•Ø 2Ñt‚JBµáÊÛNæ(áI ±ªgzêD 3ñîÆ˜ûÕ3ªgËý.{hÁÀ ´„â*´[[!©Ä¸—oÁà#&º-òçßÇÝ‚Aw šD3ØnÁ>±ÅÝ‚©ª{*˜N$†“‹ÐTµCb[ªr…Ì#GªŠTõÑŒT5FªÒ=P•5[Â@˜ª*$ž(¥pVíöXBV­Câ1kõíf­6Ifdª12•é£ßÖÉÁ·5*$(®Ñ¯ÿPYBVÂŽ€©V‘©eª&ÉŒLõê˜êe=â:'ŽqçÜ <t^wÈdH¤©`f”]ϨæFÜ-´ûƒ‹M€mDm3´ PˆØ(6z‘à *;`Œ4´·Í•Äô¿CÒ‰± ©œ2Ì# -16؈AÀçIf,áÒx}+•5Hò€ŠaØ¬Ø É$R¡™µÖ^¥•&.­ãÒúy’™j„uXнÃ.wëAªÜ ºšæÎm²T9ÎÜïN Å}ò>:y¿nŠôÉ5 6`5æíÃ@yû€=ȶ@´¥–DÛ™[=ãtº WgQLð𢭞–lHŒ[µt ý|ÅŒC}NFZÕeªJuDof!°U0@( AhÚÒ¬:Ï$Ê(+Š„Ú¹a»v I%„TÅÖ«s€ª$w¼H©ižµí¢©šÉ$ßV}RÀ†i±ô©W¥7}y:|hÀ0ƒ¸/è×rõS±°Ufž3å&ê{Ô÷W¨ï¶p‰9õ¡ƒ•™, XEÉcÒŸ#çL+3@T£vžµ¾2ªmoMó£zö©žÈúPO’E'¶\‡VOaµ×K†‚B3’3 -P|õ¬gm€FˆªdÚ­¢zFõl­ž¼Gë©‚«§äÖøÈ©MÆp%œËìÔ”Îzª§ÔSSlWy5=°¢z¶?z8Sùfû*1­eñ¹}F+$§ŽNC¼z¢ô«G.a Åñ1-vàó1ë%3Öq0-±ƒç¼<õ ËT;$•¸U8SIf=Saë@L‹}Ó'ÏÕJfdª12U÷ü'‘(e|ó]© è’g‡ä˜Êh¤ˆ—LûÒ# }ªèS=O2#S‘©d§Ïq^Œã°§Ïí8ÆÇNµÔ>c^ û EŸêy’™jŒL¥úhÝá}l“@ëÇç&*îâtBïàU¿Y©uŒSEŸê™’™jŒLÕýD_ôšž/GÔwH:ÑšM õ‡÷L¥‘`õÇ£O5¨OÕ$™‘©ÆÈTÝYY‚VQ¢§–¶ÑÄÉ$B 阊N°àêˆSm¼~¢šKT¿Yö{Väç÷ÎÔŽ¢~^ßyV¼IGªIƒÑSÕ‘-ÒSzêã˜_!·cÖ†,®ùŒ‰á3'‰²óìõøéûHPá ªQ #A DçÌcà‰5àr…!‹ÿ* “ : êu %á¢nÙéÍõ½nÆ ät~É)9ñžÈ‰Êƒ!' Ù’*M+=9EnŒ›„1rÓ¹©sÒ9È„£éœ4·Ì Ùud‡D+…á3P S¨éØ#À¶ÈñD¶7|"[“hÆù© { *É+ÂàÖ¦ª ‰%‚q5sï­f@ÈQÅݼ¸›÷<ÉŒL5ÂfÌBô.g”N*r7,o ´{‡ZjêEÅZßa ƒ·(lœgmÛ*¦¡_S[æg”ÁÄ:ØgkìC{‹#eýAØ“WÐq ù¶¢ðu±L›”§všõg£ð}¶QwÞ¬î¨>-²oè}cëÅwgy€£¯Ì0 áy0ÍZãlÕ¸ Eåy»Ê£ûè‚Ü7úcÖWרF båË$ÛÇ‚ñIËÁ H0c_’hÁ0Ul;.ÇÃ] — — —lί×y‘GI±y±^§q”•¨E~·ÇÙÌ£Dì¥n‘öµ_&E±~¥ý—Qº9¤åí;V{—y²xYyŸ•h¨å.YWç_= WYû½§Úo“Mr‘Æu­O²¢·êïû©~÷Ûq þøñŽÒPÖÖh":±8ÞD,o’E¼yEÌž—i¨éª*vúÚ¨ï–;t`Ê[;ÛA¤Ñ}œWÕÿühª'Õ\1Î$šÉíöêɘ¬/þÏ‹ª³Q¶ˆòÅä‡ÉoIŸzpDÀ IgÓã磵Û?¨ ˆpo¸®×2Åv©8¡ I±; û$Ò„qq± ‘C/¢l™Æ% cHbÅ,ŽÐdfQ ?»Œ0Ýw¾Î²ó8[¸ÎßÅýrÐ…‰²­¢œ·lUv³š_ï6¦Nƒ©zyåùún·âàú©ù<³eqµÿ5n©#ÑÂt„òf©"íu†ô¡3Ch æ4†".(u*#•±¸Š(3€Î¤1„K×FAIИ÷ª1´qò¤+·³[L&gŸ–a_X»hZ[gEš½?¹ŒVIz6ý’¬âÍä_ñÝä÷õ*ʦ“MqoçÛ¨¹¬Æ•øáçuºxJ8Ç7ç*N–Wµ z²Ò>üSÊh#W˜wÃ|.™GIg¸]Z;ˆÚÚEi²ÌVqý÷ûHsø@”Úõ›ãÔäÖ5©™qYdõÏx½ŠáSs`«ÿÄù¥}ç—$Ÿ§q o‰®¼e§T©†Ņ̃OHLUHŒ‰\Lݵº%2ŒTôo-’yÑÒL¥ñ ¬xžío=õ=„êUcÈ)7/Ed°=¦ò…æ|¡W»Fpù"¬‘„vt¼n^ô¼J¬v—Išz†Ø\kT³™ûú.ÕÑcå,a3£á=ÿ»vÇä¨ñK“ëó«užü&:J_ìÜÎÖÑ0@˜E2÷²¹¹°û|ñ´õ õndW“@Ìò0Ì¿4bk&Á"ñ‰J¬gD""…»VZèñš„^†0˜„`‚I&¡»IPM‚A”ciçL+êÓ$DL…ÄÁµ"B–«”ŽØ$ô1„Á$“LB0 -W¹ug;À‘ÖA7ÈPîÓ l4ÌÌ üi.ÀŸfQÆßþ÷uXÞry»I,½­nï²vXÝî¤Lç%m‚(—‘ 2áÓY}@/Hbj—´A,àþçm‘O½[žj”Ì@T#$*Òù€5шHªO@.4o{nó0j‹„‘P*ŒPÚžÎ$¢-r`ª÷ëQ5If`ª12éaOˆÛæv›¿[B\yÆ¥°3?ƒË™ÃmÕITämÕO•o@TXSF)e†a¦Þ‰ªA0O‘§hÇ™0«f`S¿Ç™J$ðéÁ4Û¹—ŒXdÊ•zûDEQ IT’˜jŒLÅz˜ûVÍÀ(õ<÷+‘bs»¥Êv‘yŒà¬¦g©u©š$30Õ[fªäóº€fÞCБfd£©ßÈj49!\(ÍmØH¾²ÈTjé?쬾ŸµáLjaʈny¼/Êç¯GˆY½h!6¿ÉoãóE²1ž¿´÷Œ(æ‚c(gFFÇr‚ã•S -MŒW^xŠ­{R·¿èº§ o$¾ŽtTaa#ì‘ZæÓ_z@Rà±k3ãà7)&-²¤lk忇»Á욤ӫÏì> stream xœÝœ¹–$InEõüŠGÚ¾|eΈs(ÏL ÕI¿ÏwÌ="³’ZIì²°†ðþÏGzæGâßó÷ÇŸÿò×ùøçüýÑÇsìòøw¡ÿ㣬gmãñ?ýøë¿~ô^Ò³®ÇÞù¹F}üùÑGêÏVmÔö¬åñóãouägË\Ç|¶®A£­;­íý˃þ~6©yímt®Z²çÇnù¹sóè8Áýó#·Tž½=Ö^ÏžÃKkÏR…É:{×ð_¦<³Ž”J~¦)Ì?þòÛ–úã»+×¾že×Gí"XA—>Ÿ{ô»¤º5ª¬ùìµ?êêϽXþ×y­ìgÃcºŽâ³ÿ®¥|ö__ ÔÁ£–Tûõ¨¹ê¾y §7lA--,*å­Ã´ m~™—óÐmafŠ1þ7-ÅáóÅšuíçìK·Xz¼Erk>JYå9âòÅF… õæ¥Vm¼bôx&QT;Æò¿Ì×yµtÕ¤rØX—ùM+ýq3ù›˜å”´RCÌöÏ)Lçîë³LŒ”;ÔÓ¶" ¥rÁ ó‘Ûýu¾&Õgs¹v\æ7­Äez×ÙK~»Ãh<©0½ïg®’f˜Ï©å‡Ö]ÑZ9r[ 9ûùͼQ‡»jV’X®ú]KÅáµV›ïÒD5ä1ªhãÃ7´B×Î6žA­´š‰3æ†W~3¯íYá‚ÜÅ­Äá×RŸDâÅFú«§Ð¢úçÙ%CU÷ú*úm=›~l¹HÙY¹—)K‘ Í¯ó{[•c–¢£ä#¿i¥?Þ™¼÷*}[¤»òæR¾0s-xS7¹f£ T½Í)+uÃ?´E[hó׈"ç× |ö`Æ…»{ÆYaÍ3ÎþñqŸâqŸû¬ðå?>þñ.øÿ_/i©BGKAÔó³‡ó ?béh²²{fÇ<ó´m½°–¬Ä‡¤qc~¾aÄVažïYs=WyÇôdf|Çä…©ìÙ¥×"5g©˜œÒÃø¡ RŒG±o ¨»Uº,ÒfÂ+^îâܹ=uÉŒ‘T–é9ØáhÓ©ónÁí±…FV Ž´ Jðä)òJËæðÀš°DÄXâŒêgBHoX—c†î…Ù• .]cÉ+[+`µdÁZàÜ=CN§O5#ì!.ìÑ’é¢ÃÎâ ­>ûLfB³l¼`]ÿë-ÎŒƒ©z/¿àusý„ÑAK zϘöôLkÍU C‹Ì€Ò{\TT^±‹^|³æ´Ó&¸AÃsl`ñâïÙ_¿§Æ3 Lf˜%¾±]óø)rxÇëÜ_°¯ivÀmË1A,ÌŠ½b`'<„.za&’’ƒ;8 é5UtT8j§/µÊœœæ±ôÖ llú æ–¨{Ö/ôò˜õEE)óuÆÜÍê~!…öp¾Áܳ.9|­üEæeM¤$$ÉPHNë²J”]·?˜Ÿ/Ì’Ç•²11iÉýލö^ÞœOÏ2ïç¥,¸q¤¼4ŠBÜ«éeì!éIóåÃJáM)‘=o1Î@vÄ9ZL¶Dw”Œž2o=˜ðÒø ŒoÈy+¸XpûÄiÔ6ñT^03¦Õk„´ñ>#$}êR³œ|‹¹ÌÈÂ$ÖêpU9°\Õ> ìzÀ©x†D]òéS Xp4 tDG–^˜sM@VvŒX«#Jh—]ìÚ ÁüûeycÖ,˜¡ŸlÚâ5^çrk)Q<££|5h¡‡h¾Y¶$m±ÄØA­m¥µ9` j?YG7 .(2£òö»´j“ù:\Ǿ:fÑŽ5^p˜jÂ$<½à´2_Û>N¼¨y&Ã„Ìø[Yë2›KôŠV/7 §Ð›:ÛŠC5»ƒbÔŽ–ì÷XZÃ{ˆ/~EfÒÖ˜ÿñ’¦3åÄà%[оó–vš×~Çô5•®®ÄCß`^³Ž ¾þ,ëÿÕ:ÆÖ’¾ä–ËØoÄOb”…Ö°RÝÞj Çï˜ÏËü¼Ý.¹m*¶"2'¢é†ÁNÆ4¦µ9<`+xÁ+4ºtj‚Ž­ˆñ#fGèAŸnÛF1‡`ë*fè–:¶0º6 {Y5ÀÄ \aŽÆX› c6ä¦P‘o[y`†/˜ m¢s^#dΊG$ÈÓ`»ÆbåŒ4¤ip&rGÒbùÊ¡±¡|!Äêã´,—({~ÅûP `½Ê™$Á¢qËÙ)ÁcÔ’ËäH ÛÝ·®ž0íeµ4­HœÏ–Iâ)4 ¼ÀÊ ˜P7*«%i±ƒŒ“(ØšItç÷v½|¤õ6óËÙRlC™È<}¿ö9uˆ¸øÁ¾¢àm¾@Ô#/Ä„îÈF‰£Çy ›pûØÂ “.‘ñ’ÃKêMÉ¥„ õ|OhÆØ 7ÜÙ¢ÚK2ÌÖIÖ¹·0L¶ïgÀdG©ê1ÞáŽ7rMhòà§µÏÏ“J–¤îá\Î;†› imŒpó¿Áܳ†X±~Zù`Äœ•õÎ,ÎEÙò'Ìj¡R,Êù+âM¶ÂRgfâötó…Ùö©~.R^Ä)¹©³))˜¬j«XïVJp ¾sAÒ´R‡+Åïè y2à™QŽðâÚ°G^1C$•'¸bžï°¤ Ÿß#$¼ôñn.‚˜kÛ‹@?‚ôo$3ß®+XéÆùægf [iïŠ.±žƒZýÅ3°€Î!¯[H ׸oY%¶óEƒ:œ|£RŽào:’Á÷[:¿àë%nÌy«k…ë-¯=^¯}q±ÃuÄ‹]®;¼êºåá¸Cƒ›‘Þ8öñæéCæ›ç?K…gì ¼f´)OÔÌÁü„!"½˜¦T;¥¶ãm’}ÇöRkÀ—®úÅN^uT¤³&»EWí-vš_4YÝ+¤>/Ü|w…á‘ßèTaf5?ý$ÙΞUrÐÛ{:d8oj;ñÜ/Vx±þóÆëýMkÚÁ5Ž[Íë,ÐÍ赌› œaiÜW› Nvo¸ï\ñ¦Ép?!Zå>¬¡û2€4[躭¡n4&Žà-ýàú˾)ì³W(²ý‚-ɾé=‚êI‹¶uD¸ìqé‡x>…¼Ü…,5°[Ë„¥­ ™œdë…t{$ÇÞbª7ã;Ät–ºà€WEQ¾LÇ8‚ ‡:n:Fµ«]SðKÕÆ„üæJp4""§Ø/ѸÜk„'€-á¯F6‡F9ñ5¼x«…”tM5!%âÄ>’FJX$ïÔ@8w‰ ©àvÜŠ}$X¬cõ|\í90õ Ú,ö¾Â±.­À̈|š$§GÆX* ›ô Wj¬–Æ‚ñÿ¹`»eyÎ qi 67Lâó(Óa»( ²ãñU`C¿”° ð²3ë¹ÚM&Ï#ÕC…–Î5ªu¤È‚Ëoµ¾xtU‹_Ö3gþÛYN#`Å%E˜èªaL‘!_dœ¶üºɼþkÖ¨¸ºXrÂ×’dÚe_åv>†ä·Îîê°$¸§=ÙW‡Tæ«KÝ7&":!&òÓ¾A¼æiÍïË‚œOq5MZl¡œ–‹rŸ0¤ œÊÑÈ‚à¾cÄyR,¦ìåxß°wËÀ9²ãi$¿Ö†$½™ åQ(¶"Rsªl¥cu*qVyàB+ ×ɇÉUvN|J —;;ç\#¾×ˆY8 ñé b*Α†;H*T¡Â¤øÝ½@âð3cX»g +ÅéBÅâ i!Õè "Š;`‰ðài‰Nž¾¤ƒÑ1‹Ÿ]DØž£;4®DzÒHc`¶ªFçGÇ—Wô•’­å FYq o/\ñnì‘]Lpc.>©Ä‹äHoÆñï›~eP†HCèÁ ŸT,{a$Ü%ÞÜ6vÊx-I°`ÙÚxö“ a…D Õ™½lÉ&_vðœâÜÝ&ºâAŒ"ùÑâÊ)&Áf`çÒI»$k_ñ¥ƒ"±Í~ÄÊÎ(nÁâO©Á þqÝóB¼..fÊë"óŽV•§ta´§µ¯Úd•tª‚¡ä—êŽ{$Lâ³R€¼ÓO·±.Úc9¦c‚Ø\D&#¿LY'¯B5rPVÞÔ3˜÷Mz-Lv¾ÊšßOƒg>=žkšO9±C÷<(,•ÎѦAA¨?ríºíŸ¸¡f£ùÝÚðÍdjÀòMg(‘¦ã#ëìMš%ò|¿¬fWD:IÅ¿ü®•Ü>·“õuƒÞ–2*NõŒ¤Ê¡¿àò¼èK AëGz'„‘þ©ñ‚Ø$š Ÿ®sf‡51c8á– lü椿o\¸u¥ªÃå˜Ð]¬Êµ:Rv$ž2Ft¼Ò!®åݯXh8“‹ö¦“Ì Q5r·š ɶÎÉdþ ý0‰y¿Ã\³tQØû;̽û=ëW .àç•«¤ª¡§yM覷œhÀêÈ! „®Õ3 A±ËAI„¦¥ÁcÊ _°ÕpT"îð—,a£7ìì‘MAòŒªØªl‘gËÎÜ>âñzhú “NFAs¶ËGpÈܱ\ˆ'› »r‰è ÉÆ¥㜰`ëdÁƒ¿•MΫ™²Æ)EDîU¶ÍŒö±d=`–>£iÔªÁô¾DMoðYF~¼gß3–xSMÈ®2ÓH²)ßÂáEG²bË)Tx¦Œì\ž¿Ë3l„˜žv½èóébU e=²s?>°pít%hįm{õœëD}‚d£Ô$ö¼7<5©U= µ?m;Ð8ïêÈ熇¤w+îšà £r~yü7üã#gwÜ(oWO°wœIQÏhW2B‡±Uó¦<+^£á¶¢ ÛßÒ¸rõ$lÛÑÜú©€äÑ¢µ‹"ótGE›ökÓ¸™7)¢$Ž¥w’Èðp£6.çðÖWX4–ÜT8ì`tb]“#åh!ÌOçÒ– tÍ”„äúûœ &ob‘µÞ` Ü2Fä 5({Üüð¼°ˆ‚KuR¤/yŠQÍl‰MI½ ä†muãHç¡Zv›Û=@¦t,ÃÖ»yópÀD@öyÜU-ùu0™‚(ô ܰ™Ö3nŒûµ Ý0hû ÌîßÌt¸Û…—¼º $T%ߨdj×½ÜpÜò1P,3–¬oà*QCyÃ8M™‡~Ý!¹£nì°â§]%v˵<Ñ•šØp °>Á#JÑ/LvhëÞeþ‹VpZwI‰Ûnãv{ât¾êÂ踵¸ë4 újÎèo^+Z—ÈÌëŽ' ,úfd1©!N2`Ä.YIµÝøŽ7()¡”FÏlwF[‘Œ$J=u#ð2‰Ý<]ÛHÌ(‡/²Ô•”<²‡bñN™B¹¢€Ny¹ÆìÌŒî ÙkY„$¼±NÁ¬©Ê ÔÊ‹7•ë§ÒtÀ47Hº²ˆ†d#“o½é ç¹Gb„²·´ƒŽ·¿¶›*‰6i:vÕn40ŽH<¬á¶„‰†"_J Vo@¨JN€‡˜ëMéÊ5ÎÏ®ï/û”¬›Fv8Ðkô‡}8Çñ$O8Š˜Ô=7ÄsŽ/s0­¡§{—›COgÌ•“#i³Š[6Ù­ sIõ‹U6©K6¤®¯·½`“ζ{Àƾg tß‘ÚÜ´«Dd—jÓJ™D[l©ï¿NËß g\Œ3#0‰vÖä:r\6“=a—-5x‡2%ðÐo"ãC®]óé.í\ð¹Áô=‚¨™º/pãyš½n%vwò"¸î.KHñEë¼v€0É›²–vÜNE•7˜ž¶CÙÀÐÒ[vì¿~ þgÕ€ºø~zè—º)îN<ƒ—/¸áÒ$jN@ÓúpÚKhÑÆæº°ÜRÔ•ŒQÅ¡ÄçX‹D¤`“—pó8ðòÆŠáú;p`§áõWa/j}×G51¬û­w8È.LslàZ&÷);Y|ÝàE…¯4¸úOÉ¿D˜î«k”ɪë•õÆÈA­è>R¤Hà‘Ïmû°¼œÞ⾜™–Z`ÄH0!Ó°£÷!Ëan¦¹<½§£SÁÅYxYÖ%²ÜðLáÛÝz(%¨^€ªfsö^Ú&Ñì]V)Ù*5¼&Þ!­¹Wܤ}€Œn¨ûw¼Ä‡Ó¢rs¡ üº"x®Åj×û5*Ö§˜ÊqàþJ*ŸŠHßQú¯ä)yU¯e æ•#ãí±# czËríétªnœv×ÐZtvX#ù†.P§sH|—â÷¼N~¶šÏ¨­£œÁ•®˜.ü8LÒÃg1­æÃøåêjËœx!ÈÉPÈÏÓ]Dtœ“'ª9êw½å£­ã„¡˜=¸c|Ø1`†ŒÉœw`Óí¦’°¶É彇àuxµYw2ƒú½4TGñèšÄ2dîO 醆{\˜l#P n`W]„žœNzõÌ ÒŒ'Þ­àêÂI°æçwÒí‚Ï=úzá¢×ÄúÞ02ƒÅ.L³½UZ ®§Ìtë/x]Ù¡S‚„1+L<(©…Ô&\Q*F¡ÈìÉ«ã~¤K8¤$‹Ž@bE_Ù¿u’‘º¨%è5¢ºŠNF · 3ŠýÆztÚnx×fn'¥Þ|*'©éf‘\ÐP>¶ ;õ›¶ó>ÅsµÄ¶«%Í¿lêÞØ_R÷Žœ };äŠëö•ÎÉ÷¤ÛpÏÖnØ´ÛX¾{D¦‰Úî©3ç‰ Ävàa I¸Æ­ˆ*¡%t˜þLìiü 3q0î¢^@DD™deÔÛàôc¶’»$iQÆ›¬ÛÈF/÷Í‹&58pE%?èØ^¿Új:Ysä´ǦJ«!á—µÄrP´ð›ËHCs¼äÁ9œáXËñ ]I…+½& ·ˆ­ÂPÏ,z¥g+¿<ösíýv,Iý‚©´†XŒ¢3FàÜŽvøs¸ãqaÿúM'Å<4K¶áš×<Ê £tFÌ8˜ß`zú&üŸÕÃÿ•·KvZÙ+áN(’©_#Ĩ¾N®Ã]IàtòEh¿$–o"N^prjÙùZä€~8ÙȼÒI6»ÑYœ½"SgÿÍÀ\Q°>`TN=‘&yšÅxÞL'8Eâ|t&’d–;Û|2f×ü—V$¶‹0žãm@±*×|÷ÞšÝÉ1ûB?BÉÎ{Z·4{=>Yº‡{Œy;,=ü¥\æÝo×÷*›ùÌ%¼¿êŽø5V(n…È8ö1²-Kv©;Ç-}ë€M_'£_#ÈãxÍô¦ûvÄ=Ý Qs´Âø^ð__:·:¼Ò Ö»„¡¼0¼¡µµB^Ù‘ Ïæ<¶ëÖëÎb‡å[9‡½\ò2%Ó ¶}˜ç«WpÖÔê$øÔ±ö1¦[ð)å¤bÅÇ75æŒ{zýÂ4g$íK™WqØrè ¾~̘5ÒàÕ÷­41À#•·m¾Ø ðÜÂ+œß{9–7 §“3a ©àpýûѰ-²òôIŒky“]ìU¼þ ¢éV%7<âˤFä –õ§L·¸Rá‡IIÉÝÂwq&v#P•n.Ýk³Ç·jÂŒ3ÎS;pµdœ4«Ý²P­÷hÚ¬ÜljÙÀT1†D9Ü]³ç–ÌP­»6Y¹ßÉ™S#¹Áß™¼ ù¬þ Þ¹âaÝq]â¢Ã*„VS|Û\gù3ŠS±qlê/ª åŽ$á¯q}‹â@)9+9àæ”\y¨1c†Nët0ž@(Rô]N<’÷&ÕšC)^ps©ì„NÆTg6½K2ר…Ò¥ [DÌ3*qÑVË®™ûç}Ãv J|ŽqF ¤œ¯Í9Ä$G±§çøøÈºvÄžÝ!p‰|oñ7ÖŠ²W·”Ûi‹Oïz=_ëjÎ4ï:Bd [Ö[R èéäsuÈø`»Çç2ŽY]o ;·Œúã<:‹¯ûòë÷ho×t79KΨ3ætºî BÞVYT4P´t3 ÜoؾjÌ8˜éÎ8­éÞ9çîa J&¼ÍÈ+¾*Š·S­ª*-ãSFÛ·Ñr} `Sî¦Úx‘øn3ܪþbÚ|;=è™A–ð ࣭ü#­qÂLJ´_Èÿ8¡G‰Â+ ¤ês¾&ôeþ’®®úÏoØ—(!k׈:ãÐ0Øz‡w|¸ôÂ蘎QëŠï„ÅüýŒàÛ_mQ%ÇN›pµE|÷?paœ4>±Æx“ÿÏuúoÿ ‚¹[/endstream endobj 6 0 obj 6821 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:10:15+10:00 2013-08-12T12:10:15+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/triangulation_central.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000007125 00000 n 0000008813 00000 n 0000007066 00000 n 0000006926 00000 n 0000000015 00000 n 0000006906 00000 n 0000007189 00000 n 0000007230 00000 n 0000007259 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [] >> startxref 9065 %%EOF opengv/doc/addons/images/triangulation_central.eps0000664016516101651610000004421313344612246021376 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/triangulation_central.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 11:38:47 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 659 465 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -26.375000 -21.049123 translate %%EndProlog 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 45.850000 17.550000 m 46.150000 4.700000 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 27.650000 16.225000 m 49.400000 5.175000 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.625000 16.225000 m 30.980637 17.726206 l s [] 0 sd 0 slj 0 slc n 31.322944 17.879343 m 30.764443 17.903365 l 30.980637 17.726206 l 30.968626 17.446956 l ef n 31.322944 17.879343 m 30.764443 17.903365 l 30.980637 17.726206 l 30.968626 17.446956 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.650000 16.225000 m 27.638993 19.813199 l s [] 0 sd 0 slj 0 slc n 27.637843 20.188197 m 27.389378 19.687433 l 27.638993 19.813199 l 27.889376 19.688966 l ef n 27.637843 20.188197 m 27.389378 19.687433 l 27.638993 19.813199 l 27.889376 19.688966 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.625000 16.225000 m 30.736892 13.868853 l s [] 0 sd 0 slj 0 slc n 31.035864 13.642489 m 30.788144 14.143623 l 30.736892 13.868853 l 30.486325 13.744993 l ef n 31.035864 13.642489 m 30.788144 14.143623 l 30.736892 13.868853 l 30.486325 13.744993 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 27.750000 16.175000 m 33.978894 12.996277 l s [] 0 sd 0 slj 0 slc n 34.312914 12.825820 m 33.981192 13.275776 l 33.978894 12.996277 l 33.753916 12.830416 l ef n 34.312914 12.825820 m 33.981192 13.275776 l 33.978894 12.996277 l 33.753916 12.830416 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 45.850000 17.500000 m 47.424821 20.518407 l s [] 0 sd 0 slj 0 slc n 47.598284 20.850877 m 47.145354 20.523226 l 47.424821 20.518407 l 47.588647 20.291943 l ef n 47.598284 20.850877 m 47.145354 20.523226 l 47.424821 20.518407 l 47.588647 20.291943 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.800000 17.500000 m 49.081575 15.548793 l s [] 0 sd 0 slj 0 slc n 49.403901 15.357140 m 49.101902 15.827562 l 49.081575 15.548793 l 48.846364 15.397794 l ef n 49.403901 15.357140 m 49.101902 15.827562 l 49.081575 15.548793 l 48.846364 15.397794 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.875000 17.500000 m 44.039660 15.181676 l s [] 0 sd 0 slj 0 slc n 43.806897 14.887659 m 44.313260 15.124506 l 44.039660 15.181676 l 43.921237 15.434858 l ef n 43.806897 14.887659 m 44.313260 15.124506 l 44.039660 15.181676 l 43.921237 15.434858 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 45.850000 17.450000 m 45.974184 12.911621 l s [] 0 sd 0 slj 0 slc n 45.984442 12.536762 m 46.220672 13.043413 l 45.974184 12.911621 l 45.720859 13.029736 l ef n 45.984442 12.536762 m 46.220672 13.043413 l 45.974184 12.911621 l 45.720859 13.029736 l cp s 0.000000 0.000000 0.000000 srgb n 45.700000 7.575000 0.187500 0.200000 0 360 ellipse f 0.100000 slw [] 0 sd [] 0 sd n 45.700000 7.575000 0.187500 0.200000 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.387500 7.250000 m 46.137500 7.975000 l s 1.000000 0.000000 0.000000 srgb gsave 32.300000 13.102500 translate 0.035278 -0.035278 scale start_ol 1024 5440 moveto 97 5440 lineto 97 5907 lineto 1024 6171 lineto 1024 6828 lineto 1024 7471 1195 7955 conicto 1366 8440 1685 8761 conicto 2004 9083 2467 9245 conicto 2931 9408 3516 9408 conicto 3661 9408 3815 9398 conicto 3970 9388 4118 9371 conicto 4266 9355 4391 9332 conicto 4516 9309 4608 9283 conicto 4608 7808 lineto 4190 7808 lineto 4002 8542 lineto 3943 8603 3842 8653 conicto 3742 8704 3593 8704 conicto 3450 8704 3330 8616 conicto 3210 8528 3125 8328 conicto 3041 8129 2992 7812 conicto 2944 7496 2944 7039 conicto 2944 6144 lineto 4160 6144 lineto 4160 5440 lineto 2944 5440 lineto 2944 576 lineto 3943 422 lineto 3943 0 lineto 358 0 lineto 358 422 lineto 1024 576 lineto 1024 5440 lineto end_ol grestore gsave 46.275000 15.452500 translate 0.035278 -0.035278 scale start_ol 1024 5440 moveto 97 5440 lineto 97 5907 lineto 1024 6171 lineto 1024 6828 lineto 1024 7471 1195 7955 conicto 1366 8440 1685 8761 conicto 2004 9083 2467 9245 conicto 2931 9408 3516 9408 conicto 3661 9408 3815 9398 conicto 3970 9388 4118 9371 conicto 4266 9355 4391 9332 conicto 4516 9309 4608 9283 conicto 4608 7808 lineto 4190 7808 lineto 4002 8542 lineto 3943 8603 3842 8653 conicto 3742 8704 3593 8704 conicto 3450 8704 3330 8616 conicto 3210 8528 3125 8328 conicto 3041 8129 2992 7812 conicto 2944 7496 2944 7039 conicto 2944 6144 lineto 4160 6144 lineto 4160 5440 lineto 2944 5440 lineto 2944 576 lineto 3943 422 lineto 3943 0 lineto 358 0 lineto 358 422 lineto 1024 576 lineto 1024 5440 lineto end_ol grestore gsave 46.864442 15.452500 translate 0.035278 -0.035278 scale start_ol 1024 8768 moveto 2688 8768 lineto 2185 5632 lineto 1514 5632 lineto 1024 8768 lineto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 42.800000 6.727500 translate 0.035278 -0.035278 scale start_ol 2693 5795 moveto 2836 5893 3009 5981 conicto 3182 6069 3387 6131 conicto 3593 6194 3840 6233 conicto 4088 6272 4388 6272 conicto 5667 6272 6289 5525 conicto 6912 4778 6912 3166 conicto 6912 2426 6745 1818 conicto 6579 1210 6233 778 conicto 5888 346 5360 109 conicto 4832 -128 4108 -128 conicto 3756 -128 3417 -85 conicto 3078 -43 2713 49 conicto 2719 -24 2729 -151 conicto 2739 -278 2742 -421 conicto 2746 -564 2749 -701 conicto 2752 -838 2752 -938 conicto 2752 -2304 lineto 3653 -2458 lineto 3653 -2880 lineto 165 -2880 lineto 165 -2458 lineto 832 -2304 lineto 832 5568 lineto 159 5722 lineto 159 6144 lineto 2680 6144 lineto 2693 5795 lineto 4992 3137 moveto 4992 3846 4901 4317 conicto 4810 4788 4654 5064 conicto 4499 5341 4294 5454 conicto 4090 5568 3862 5568 conicto 3531 5568 3248 5496 conicto 2966 5425 2752 5321 conicto 2752 713 lineto 3278 576 3849 576 conicto 4434 576 4713 1219 conicto 4992 1863 4992 3137 conicto end_ol grestore gsave 43.784076 6.727500 translate 0.035278 -0.035278 scale start_ol 6848 3584 moveto 6848 2624 lineto 640 2624 lineto 640 3584 lineto 6848 3584 lineto 6848 6272 moveto 6848 5312 lineto 640 5312 lineto 640 6272 lineto 6848 6272 lineto end_ol grestore gsave 44.790634 6.727500 translate 0.035278 -0.035278 scale start_ol 2941 -192 moveto 2711 -192 2510 -107 conicto 2310 -22 2165 125 conicto 2020 273 1938 470 conicto 1856 667 1856 896 conicto 1856 1119 1938 1319 conicto 2020 1519 2165 1666 conicto 2310 1814 2510 1899 conicto 2711 1984 2941 1984 conicto 3171 1984 3368 1899 conicto 3565 1814 3713 1666 conicto 3861 1519 3946 1319 conicto 4032 1119 4032 896 conicto 4032 667 3946 470 conicto 3861 273 3713 125 conicto 3565 -22 3368 -107 conicto 3171 -192 2941 -192 conicto 3264 2560 moveto 2560 2560 lineto 2188 4608 lineto 2809 4771 lineto 3058 4836 3280 4943 conicto 3502 5050 3669 5245 conicto 3836 5441 3934 5743 conicto 4032 6046 4032 6501 conicto 4032 6956 3953 7278 conicto 3875 7600 3707 7805 conicto 3540 8010 3284 8101 conicto 3028 8192 2668 8192 conicto 2353 8192 2113 8110 conicto 1874 8029 1690 7907 conicto 1408 6592 lineto 832 6592 lineto 832 8547 lineto 1339 8680 1849 8756 conicto 2359 8832 2964 8832 conicto 4445 8832 5198 8261 conicto 5952 7690 5952 6542 conicto 5952 6110 5834 5716 conicto 5717 5323 5474 5000 conicto 5232 4678 4866 4436 conicto 4500 4194 4009 4059 conicto 3440 3904 lineto 3264 2560 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slj 0 slc 0.000000 0.000000 1.000000 srgb n 44.487500 18.650000 m 39.662500 20.675000 32.812500 19.800000 29.304416 18.179176 c s [] 0 sd 0 slj 0 slc n 28.963994 18.021893 m 29.522745 18.004656 l 29.304416 18.179176 l 29.313034 18.458552 l ef n 28.963994 18.021893 m 29.522745 18.004656 l 29.304416 18.179176 l 29.313034 18.458552 l cp s gsave 36.150000 19.252500 translate 0.035278 -0.035278 scale start_ol 3392 3712 moveto 3392 640 lineto 4515 467 lineto 4515 0 lineto 306 0 lineto 306 467 lineto 1344 640 lineto 1344 8128 lineto 221 8296 lineto 221 8768 lineto 4411 8768 lineto 5510 8768 6248 8588 conicto 6987 8408 7432 8084 conicto 7877 7761 8066 7309 conicto 8256 6858 8256 6315 conicto 8256 5903 8164 5530 conicto 8072 5157 7865 4843 conicto 7659 4529 7321 4287 conicto 6983 4045 6484 3895 conicto 8855 640 lineto 9792 467 lineto 9792 0 lineto 6958 0 lineto 4412 3712 lineto 3392 3712 lineto 6208 6303 moveto 6208 6830 6103 7170 conicto 5998 7510 5768 7708 conicto 5538 7906 5177 7985 conicto 4816 8064 4311 8064 conicto 3392 8064 lineto 3392 4416 lineto 4344 4416 lineto 4862 4416 5220 4521 conicto 5578 4627 5798 4854 conicto 6018 5082 6113 5438 conicto 6208 5795 6208 6303 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.117647 0.878431 1.000000 srgb n 27.737500 16.200000 m 45.301860 17.416368 l s [] 0 sd 0 slj 0 slc n 45.675964 17.442276 m 45.159887 17.657135 l 45.301860 17.416368 l 45.194430 17.158330 l ef n 45.675964 17.442276 m 45.159887 17.657135 l 45.301860 17.416368 l 45.194430 17.158330 l cp s gsave 36.675000 16.477500 translate 0.035278 -0.035278 scale start_ol 2874 -128 moveto 2382 -128 2031 -11 conicto 1680 106 1457 311 conicto 1234 516 1129 799 conicto 1024 1082 1024 1414 conicto 1024 5440 lineto 221 5440 lineto 221 5880 lineto 1168 6144 lineto 1946 7552 lineto 2944 7552 lineto 2944 6144 lineto 4238 6144 lineto 4238 5440 lineto 2944 5440 lineto 2944 1552 lineto 2944 1131 3118 917 conicto 3293 704 3577 704 conicto 3796 704 4012 737 conicto 4229 770 4416 809 conicto 4416 232 lineto 4324 167 4147 101 conicto 3970 36 3756 -13 conicto 3543 -63 3310 -95 conicto 3078 -128 2874 -128 conicto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 26.375000 16.077500 translate 0.035278 -0.035278 scale start_ol 4208 5632 moveto 3407 5632 2779 5000 conicto 2151 4369 1850 3526 conicto 1550 2683 1550 1898 conicto 1550 1194 1870 789 conicto 2191 384 2765 384 conicto 3260 384 3694 630 conicto 4128 876 4676 1460 conicto 4889 1327 lineto 4288 552 3700 212 conicto 3113 -128 2365 -128 conicto 1429 -128 915 400 conicto 401 928 401 1877 conicto 401 3440 1590 4676 conicto 2779 5912 4275 5912 conicto 4876 5912 5277 5606 conicto 5678 5301 5678 4835 conicto 5678 4583 5491 4403 conicto 5304 4224 5036 4224 conicto 4515 4224 4515 4728 conicto 4515 4861 4615 5080 conicto 4716 5300 4716 5366 conicto 4716 5632 4208 5632 conicto end_ol grestore gsave 46.625000 18.442500 translate 0.035278 -0.035278 scale start_ol 4208 5632 moveto 3407 5632 2779 5000 conicto 2151 4369 1850 3526 conicto 1550 2683 1550 1898 conicto 1550 1194 1870 789 conicto 2191 384 2765 384 conicto 3260 384 3694 630 conicto 4128 876 4676 1460 conicto 4889 1327 lineto 4288 552 3700 212 conicto 3113 -128 2365 -128 conicto 1429 -128 915 400 conicto 401 928 401 1877 conicto 401 3440 1590 4676 conicto 2779 5912 4275 5912 conicto 4876 5912 5277 5606 conicto 5678 5301 5678 4835 conicto 5678 4583 5491 4403 conicto 5304 4224 5036 4224 conicto 4515 4224 4515 4728 conicto 4515 4861 4615 5080 conicto 4716 5300 4716 5366 conicto 4716 5632 4208 5632 conicto end_ol grestore gsave 47.409266 18.442500 translate 0.035278 -0.035278 scale start_ol 1763 5632 moveto 1937 7764 2044 8177 conicto 2324 8842 2792 8896 conicto 2966 8896 3093 8783 conicto 3220 8670 3220 8509 conicto 3220 8177 2044 5632 conicto 1763 5632 lineto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 37.500000 19.550000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore gsave 38.034500 19.550000 translate 0.035278 -0.035278 scale start_ol 1201 3840 moveto 1319 5303 1392 5586 conicto 1583 6043 1901 6080 conicto 2020 6080 2106 6002 conicto 2192 5924 2192 5815 conicto 2192 5586 1392 3840 conicto 1201 3840 lineto end_ol grestore gsave 37.475000 18.435000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore 0.117647 0.878431 1.000000 srgb gsave 37.450000 16.700000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore gsave 37.984500 16.700000 translate 0.035278 -0.035278 scale start_ol 1201 3840 moveto 1319 5303 1392 5586 conicto 1583 6043 1901 6080 conicto 2020 6080 2106 6002 conicto 2192 5924 2192 5815 conicto 2192 5586 1392 3840 conicto 1201 3840 lineto end_ol grestore gsave 37.400000 15.750000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore showpage opengv/doc/addons/images/absolute_noncentral.pdf0000664016516101651610000005510613344612246021034 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝ½9²%»²ž©ç(r»=0Êõ®H+)Ëø(äŠ%Ôôéÿ÷{D¬lh,ùÚ1;;Ý€@ëpxûÿ|¿¾Ê÷Kÿåßÿ|û?þc}ÿÏÿ÷Ûý>æ×<õûÿèÿû[Ý_­Ïïÿß7Jÿÿò­í5¢Vü)_g|ÿç[ï­ù½Œk~Õñýç·}›µï¯U¾ÏÖÎWíQj÷s¾Æø>vü=“RužòU÷÷^wÿ*3JÕ~Ú×ÜßëU××8.µËþÚ=jŽõÕ&__kï}ñu¥þkvxíëúšã{™×øê*=Úh_¥~ÿ»s£_û«”ïeÕ¯ºEêTÓm~EF}±~]©³VtLƒ|›-g}­þ½]1G³¹å¦ù T[_›†Ë<š¥võ&L4\祱ÖSÚ=Âès4Õb5'êݘÓ}ÌR+>ô½÷¨öYhÖËSºVŒ >s—Q5-òžÑ±Xé¯ÓßÿøÏo³kÎ{Ìý_µDs³¯þÕ΃™}ί« ŽÉÙóuMÁ[Ÿý5b†J b+\# ôù¥£ ;D«ýn.ó{ Ö»~õ%bçè;VP¬G ðÔ¯“å/÷ñ쯱¢D=Z¸@wv×—r!1úbéf«ë¯˜ØF—1­iù»Æs:˜8EeNlö fÇ·¿bžZ£¶Ø˜ż_¿kýiE³ñ‰ˆŽF‘€×WÑÂÄÑ隨siøGW<ìÓµÞ¹\#&lk©vl™˜¸ö‚Qa\Çk{ˆÝØ‹ásÇÖZ‚6·jÔškqi0A×÷=âC—˜Â`ƒ¥Ø#XŒ¸(N@ R~ôhÖz¨DðCSð.ú`€S'!à*îW5š_"kÇi[Q¢ Ç"ÚOˆ€øÜ€“·¨µw 60úyðP »%à©ݰŠïòñ³æ‘E?¿W±ÄKŸMÝŽÒ-XQ’O3å&öLp0a­¾ð„÷~ÁhOï=m‚ù,ºù&0|p ®í«o @‚ÁþjE]˜ÌØ ž|Ó%¸ù€KŽ7Jê{™1û±b qëåÛmkŽc¦†Z.îâ¼-ôPŠA«À,Zå¢Mq4g=^å™Ò‹N<%OÍ€»§M§×¸—­Þ5¦> ß™÷¬£>[I}1ß¹j ¶•KMŠg“{nÍ]hE`Mò)`í”Üg݆—@±ÇY~¨büc~¾ Ðßu“w0G˜X*:´Åì\=æ¾´©‘mÙ¬:ó´ÔE±ùýLÌ ZZñÀÿÄ<µâGuù£å³æðÓ–ZK;}¿¤_L.ŠTíˆ_¿œhaâ¡Gô Ž>®Á^ÌŠ²M e5m«Àä×|·Æ Xê›æ!z  ñN½tbõjÐyŒs9€›^eÅѼ|ƒ -º1ôÞˆCº´>ÞѲCãµÇ†<.çH·uOØŸé`ÃŽóÀ?<ñ¥|”¨)¾ˆøF­>ùÑ»âaÄëíšþ* ÎW-îUœîg¹ÅUîö¹f9zjþ4½k:ÍqŠ;_9¦*F?k}`µ ;ÛG‰˜›˜EÎ;So,ÕˆñtïëØ€Ú¨3Ž­(—0æ}ìï¿/)—oЖ¥þˆ:—äA]ËÖë}ˆ°õ¸$Õ‘ì$V)N^°’æ\EM~|Ó “*L׌ÆA_%hXÀƒmLͪ´ÀÉþñ­Hà0¨±E.Í’:1˜®"Ñ>Z‘ÌJoÙ¡ C~½êé:bIb(E’xóÞpÔˆoG»o‰%ŒN5¦uë¨Sñ˜|#ù×P ìZæèdšˆ ÒýÀ}.ßÎ/F qs’wIq Ã"i[pˆJ§D)Q¼K—]ïñ²‘ôDõ¡™òAƒï¥}™ºi–à‹“7õ:o’h%bÖýj:бWÚä½Ô$bŠI j¢×·Aͪ$6íù=6-“ÚâØjÊ⚘’bfÝ¢_n±Óâ‹zÝW$FA ‚Fo Î4é-f›è6ßÕb³X{­n †°zïpض6½„˜mBD x¢µ©m&x_¿_"ÔØ4§¯SátÞv±Å2ÕÜ-‰“%Ì‘4¦u@[}瓎ÿf’DÍ&:¬©ÚUÆÞ8ûƒÈG”Y×]\‹Ã<µªŽ%¿[~0£_’oÆ&]V ™mý‚‰ÓÔEÞ—X3oíÄü~ª£{+®K¹ÅŠ>Vè{éSÒLÉã*×_ ½°÷«H‰¶Vp]Ú«#8!ñbŽJh|øÓÔ‡8™Pædio˜zó]wP,àÎnŽCѺh€Äĺ6Kœ»ÆlˆÛŠˆg/ž Ñ„yøÁtÇÕ—¿]5‰Ç·ÐdKŒÆ cã `+ëc]|n°TÌrƒýzVx´êμk.NG“Ó«&¾©µ@p[> AcÈêacOÖ€‚þõú–ÐͳTãø¶îNõ¢‹B5íP„Êf}V©ñ€¿­"|•&²<$3麧¹Œæó{ÀGÏÏ€a1wÐbXþ½8ìïU™•Àl•ÜKä´|†æ0—kÀżr``cSE¹v S×lÀMwÀK[1àn.*Ö#v’C\ëÖ]9§á!8Ž÷h¬ qlFyKH<SB'/Á1¬-̸±.>±c‹uaDL¢€Äã;„Öãd¸‚1b55†Ö:n¥`LV&n¬b©íÞŠ1t1ÑdEnòßèœgÀW{—âÀ4†*üÐ)‰›z¯Sy^z3sdciîZ‰ ½fd‹1ŠžÞ°*ͧ w‰Ø*šXÁLlãªâ*síôô(þ†ÞxK -L1@±_º;)–Åk˜¾]B,à™m2Œø»¡òÔhNîNࢉ¹ØÀúäECY¡j ±ÅbkÇæzϲ_4!Uð„‰ÁïMŸ6Øû†Å¯”§‚0±VKª+6mU›qêÚù# †´ Á"†þÌSkÞ.-ߘ¹ÙYKã B-÷£C¶;_%k`>÷Oï 2±‰‹ŸÞ/&¨M×bˆú ŽÍÝt4ãÅéc0Åi&âU.z0P9ìeEU›¦—DÀÅ L”ª0yH¹xPo±ÊKd‰oð’V ÆvIÈaç[œÍªâû3lZÎòNI°·mù(ÛÖpãíÊ )ØÙ2¬}å8ê}ôéˆçy–{Æ`³S‰ÑõÒ<½P`âcú`pC5±U˜q±ßÁ Žåóá\Íçy4Kú<û þýY+=EWýþûj"¡íÁÍùÈÁ‡W‹!ñ^5æç¦ñ¾ƒ¨ SݨSÀÁc\Ü~sK¸€Ä2®OIFÄ#ãÔÖ7§%™]ôx§p¤ÇTIN:—J•.QOæµS(ÚgèIí·Ÿdë]Ÿ¶mF‰X`?ô â‹®G`ÊxÅ÷˜íšÒ‰¥>õ“0§yÍ*•ꮚ®˜¾aÕˆ]Èîq!$¨'…æy%ÜÜ£M“gòÔ8åDZ²‰á.l¯Ä啦QÂѽ™»æxg§ZÐP=Ôg®v‹TÒ¹9üN;8µ™©Pq‹„\Ó;Œ;ôo˜8–M´sé®*º~£C4‹8jÂý° õ^ÕÛáÞ„‰mf&§i`’ALÏn}ÀÜR³~Hч>¸zÊÝ—çnY”cE™þ•S%Áàú€[¹WüÆh»ëñ)4=äƒVµnÄ~ƒ^_¨ó«x³ƒeCó>—CÛ|ß{pZމ]:}÷ñYÜAKcrÖŽ·DGÝ=ÃïI½Ô™žÆ~µœ P"ŒØ—+Ô”†M$¿˜Ä°EY·åÃwIôÚLÐÒY=ìw2Dƒq¹Æé3o"M@O;Ëçt_cl} 6õòôo¨—n‡z8jH’<׃Ñ[™†>Qw=ðÓR-rœÀ­“£]9 ™ÖôæõÕÑÓª£%Ë$ñTâ]íu6rž5GÑàE=.M­Z„LÇ„MÞÿÞW–@ílÃâÂbuÊ9îTgÍWJiÔmÝF·‘aÄñ›’Ìw‹(­»˜Ã²X;ú g9}¨<ã\}yØ<ã@ƒÜÉ yhЕbÏ?1mØH«ró¨†z²j^˜•-t CÚj˜;MR\Ê£6ƒ]Û°ôP\º#E¯&lA ÝÂÑUWžGñtA»E¹d­ì›\×+#éØƒ‰_Ìnç…Á…RP[$övnÆhîk¸ÓÑ]Eíz×S·Yµü¦Ú^Eƒ¥‚Eü/ìG°¯?0â¥T hB„~·˜O‹csù2Ӆ̡ޱE}–/ºÜ¸.¯K„N„2%ÍRµÄ¶A¥Õ#ŸmXàøƒ~ê uïfsFœâȘ”«X^;}ô–§¡™ÅmRˇÝ2äàæà_DÑ@ˆAz¹†îú„ÍW ; [È!á¼X '—Øß@ô|”É ã±ÖæûL l‡ì,›n~ˆ¿âòÚGB*ÄÈ®ÀˆC/u X¦ÐTAB•õÀôúÆl,Zù¦Zèhþ™8Äo©CLmÌÀá‹&˜ )Ž×ÿ‚€ ÄýÆ”nQF¬‹ä'GŒtñLÐhê”n[@{ºE•Ö1Àƒ(?Ëá±lôéF\×g‰™âh%hÐ?«¸É†YmÀ ñœä5e|Â×}boŒÌG¨Q¿ˆûÒ'ü|cß—~qäŠkŽÆÐÁ.Ú†N¯E6Öù„yÓÓÆá= ܇¬[&4 ^jLúŒC‡|ðX Û|zÅ6ÌÜ]Iœ²„æÎ*9LFqKª¥‡zŽýæŠ «Û"„XðC÷ÅÊu œfC¡"eN4÷=˜µÁ}Ö:¨%‘ZÜÁ—îuîÃ]@â!Yyó˜ÿ|[3å?O¬ê/8 ´§õ6ª¾ÈŒþ\œýàôØÒÿ<˜v‚F;eˆ7ÀÿÌ> :0ûBHûÌ[kwé–Ó¥˜©Y C½à#»¹Û#Æ'ûÃõÿ‰±Ï™G·éŒÇ<{`V_´…0 ?AÅ–Ø¥}_—Lðó³=ÀŠT¨KÍA^r“Њ¡uµáùEÀœ¥ŽÚlSA5y¡”¸Ë»à:ðu¸Ùü”7"Ï’»…e²[Ä"`äo*¬+'ºsiç«Bó$]-OÀû[ÕìíétGpÃ4ýŠÍ¸T\wËMãÅÑ\0'jv•”Ä9öw¸J3·µ.3ï¯ksE¾›àÁ<%Úíø˜¼[çD掠ÏMùóm*ÌÆö*&0¨9ûöFHëv´æ¨~ºÔ†qÏOñ'j´Ä°˜’Ø%ðXáÄŒ$Ö´Š7÷.b§¥SÌÅ.¸4œ)"ÑØ¿úòÝ*ÍyÄè1uð¦ø†½ ¥Ò°qHIøÇ;ÌÄ|¼nûÈD­ƒ[¦Ùi$1S\’žãW»Ô+®™® ÚÛ%[KJF­ãdø]^?òjÍÖ;V{çxØ11zi‰¤¸÷cì> ™YÕiQÆÔëÑzÍÜ)÷ÒH±¿ÿ¶vb'Ëíž5k‡eŸb:+M:?-à%¬ôfÒ[;îJ>d‡£a_mßÞíK ˜ÅÚ¶_¶l`!se Šõ²³’“R; »8íj£f1óñ„™W<§fGòQµ<ýñóò…½2ý¾Dq'KÚUªèQ.µI5©ŠR² ”ú§´æ± öV½zü ûWN»¥E©Ôü_àðnÌÏLïÖ¼¼µF}hxb¤l­¿`l3ÅoH½{$ÖÑ×ó ö­ìöÆèX¢Í«ð-¬Nè‹'fÞxPMm¼£öx> FÀ¶‘(çv IÉ„àöJ¦b>T®`vÃÐ, p>JCDR:þ,ÞL°‚׺¦1…;K ©_Úr';àöõÜFÄF‚î2æà°‚Þr œe8é®&‘&`MÚ·á¡‹ÄZMÁ.žà…Ý•ÈcChü‰©°P1±hvÀ`ß0EÔ™(†R=ð©&4Ü8O±Ccž6K.xˆÖŒjo˜™E“ó–¸ôÞw›S㺠Þtá¸Æ5¼9´t‹É~C“]ŽºÏjª‚´„従uôuOѹÍéz’€‘›1-÷ÇäÁqÂ"à]˜ÙBÂ2ƒ¾+€H€~zEeAðÌ{œîZ`ðsé^‚¡åÒ÷ý f¢þ‡tÛ¸û/˜»ÖsŸ–?ðb-ë¾p4 IDd2ˆÔ21??0ýJÌS«chð‰™+ŽF×¥ddVM´u¸ªØ1 ðä§jýн`ªš,/ªÙx¡m›3Ô]ÑV7è¸EÔ*ŒÔ¥ö S“)ÈB^í^o šT|ÀË´Ý…Õ=õfn¸Pñݰ*˜Kxr'pÓ¾¶Ôno65û<%d¿±Er\Á$„4¡z_t׿ª§s†"T=O5梤§‰žE0ì:°íQoÌ:øþimŽgöÃÓ¶É ÆömñvEd#c&+FV4öйkÕã·è3A;°€ Le:+F:1y'W«r nlnÙµ^ç- MƒRñí‰e¼\aJg‘ûA+>±A ˜ë àjް”TeïàPšútað%Þ=¶ÃÑš0 =7²À D¯r´x§UW¿áÕ,Û|=9NÖ3xÜ¿ažóôÔú3öeY¦?¦¹ÅÉúÄLè½ÎåFÓü7Ì[+OáGË¿žx¨@iôqÔNݵ\¨.oÌÏÌ97&kIâŽ=Í‹‘øiü‚iè8«RI¤ ‘eŽÖFº©TÙ+Êâ¤Ù€ªbTTJ©èŠTÂA1%'E`U‹4ìñî—ÖAº2™ÛÒÂͨ2ÆÀ+µ¦eÓ¿!q­”_ra—LêÓ•Ž2ÄKKòbiÃ]BŒÊ0lËò¥ñ?Þ²ÕB–æµ=¿_Ã^2ˆÌ¬ó§ÂùªFt¹6È-zÆ­FB%~¿RmQêg0…(ª‡Œ0Áï6î\Òä>1'·×œÜ zs¦›7q ¸E‡œ4 ž"Ló`ºj(Žwȸٟ)–‘´]ì^PZ®XáàUéŒ×§£Æž%ì™N“¸ÈJ›^Y‘÷„vѱÅa[ö¹ö¦‹—¥*µø17$ü^”hÞ3XÈÕÀTYfm*Ìô£ofZ˜¿M×mgœóYe{T|H.=<økå77„Œhz7<ð²Õk°äl ±{CÂEÙ¹€9VìûÄm—ο6`å4Û©V›¿Ð›ç*†)â#ƒŸ«y“¨‡ý¸Â¬6dfStvòÌ*‹é—®…d¼Šý^Tû9T•É ¸¯e3-L€´vš|Àsû'â`„Mƒâbðä+ùÁ&¸§;wKoÜ 4êÁX\äø±0&j”FWªKŽ{Eë/Ðd]¦[ X"ÁF¯pc Ê€£!ÇÜ8Pw 7kMö®Ù-fæ²ôiÕj•ja'÷3-7ˆž½ÕµXRè™3çò-¨@±Î륎é…Ñ>àÙíE÷b–cW –Ò²,d{ •µï]Û}xŠÌ*€8oȉ‘õ鈲Þöla6E©J°3zX`G©QYX±)µ’MÿtáâwfÅ0ÄàZ¹Í×s.<ýw2=ŸYÎÑN¸zý ­À`k^±Y†;g׆êÓÊÓÍöSótK‚¥Ap”ì'1Äê.{‚ŸmäsçàÁ4ðȰ¶+&ê6’!ýœ›¼s#ýÑ{¡Øy{Û¿A|Ò}r¶Õ¶H›Þ zrä£é dÉ”w;5B‚fq*pî^ xjÒæéÙ{zÿ»O=ÅL6qµ+¢·‰`GÀGá†Yóõ|Jtâ@1 ¶þÀVî^SÕÐU[<¬È²‘M‘Ýç'mâ“rçºO»¤Y¦(3d :U¦E[ŠÇÇoODEñ­×ž_I5»„¸kè­äµ[.oñ‡oý¼>àä,¤qZeáñ5ä“¢ÓÒé\µ¦$Xô"–|I7¼¾/ÝÓò±“”½Ä}±§Ý‡ò-9AÛÓO5ÔOÀ`÷=aPå{±ŸOþÞì(¦êÁ(,ÑÀ9ì×\¡™•Ð';5:K!…ØúÞ¦/¦@o–ú¤œ%·×"êr””©‚Î$+»›ÛlÅK#U««ïžã¼JÞßùU„Y½°Tñ-anž~/}cb&G‹·îŽékµâäÜ53»À{ßGõÁô¬qÙvɾ|áû¼åw¿Ï¶º¹ìöDZ-{hTŸ]Ù"}—ͫ^ŒLcT ú ù çö€­­A'.«#Åá°á.´Žt‰³k˜;IR–˜Í'¡\ŒÊïÊ!ß½<ì¿PÁŸŸñ‡®<)3dƒˆ;‰‚o"UKÌÐ8 V@Ëñp¾Õ¹bæ§>nº"-J Xx›Uìî†KãÍPy‰ªxå T¹•‹™mf5+þꇕ÷\ÕcV§Uî2Ô–ežÜvųï«§ýÙÐsMŽŠ®¡Ã'ÎŒoŒn w㪨HŸ&5ÌV=±‘¼#.^ßœ…¶’±|a¦“Ûì-Qy» ®Ù…Qìh8ªoĪ`NÝáy;¦ƒuJ,7ŒÁV¦Ê}QÄ_Ú=“¦]M‡ôªsÏÉ6èBàÔ M]0B\å!pƒ*oœ·€c¯ÒÀIþ—.­šgPC¿øÄr¨†âøU8jÓ)'±é:Àêy¥­8|jÎí,.ü)1»=°tÙªÉû¶Ê¿¹eóE·qÖùöZΓlö¹¯s 빇D,:`Ó¾Èêd¬9Î#õö®§ ”Æ€Op>l&¿¡W ŽÈÝk=~¥}ÇÕRÌô”è<9£žÉâ”ËÎM‡ÇhªF´/å¶=>Àgù^Œm†šM Ù bøð(¨Q³Ž*±â¿.*^xpRµìuƒ\ÌŸßEÝ«KÚ$Š×§\|¸sD|2¢Ú¬…;ÆÅ(ž6®jñÝ®Ý÷b°7ÖœUœ?£6AÙHGûÂí¯/–dtG&ïºÜÔ…b&@ÑÂcO!%¤„݈ 1½¯øÝ[¶r—]£ô†¶/7,1oŒ£uÆôþXæ;ëº¼!0ŠÂÆ"* ›>!¿nÑÔ /(ÓZ¤à"çI¿h4­88ˆ­ŸˆÐÝ¡j­–#}ô(¾§Q?´ý9ÑBï%ºUÉM?}R;‰«=ž¸œ›´+î…+#!J ·&.œ,·Bß~‰Ñ4åÄ¢\ïxW¤Ÿg¹öËI5 w´ãS/ŸL)ˆÚ6¼p§t`*-gC 縎«FaÙ16õÒ’@&¬­-S–·Nåç;Þº(”·C(È#‚¨!§AܳÔ|[Û{ì·Zÿ€®‹Ôƒó§¸QµÐ6ŽŠ•´—ŽF~ìù <æí5ˆ2¡£*ë꣕ ƒ€O¸W|¯êêmá“Ö°…`f5/jA[” %-¼ø²ÂÁ©—µ}†øðÊ9ê)a“küÕÒ_HßÃë-O(éIôê—¬Vn3RATnh¦¡àG?.< 8CžÀa¢'”Àå“;aº6XI÷ ‚Éãqé‘­Ž1Ïû]½gNœrÐ;È5ª8äŠ^—²çê&?.LùAE[àJ·ž /¶K «†¹?J\.ô-Óa;Ä3à²$ãáÎNX.чê+^^[Š=B£V±í˜q—ð²IÖ¨{7Ø. Þ_Î'‡e3¹IkÄ Ú½Iz%¼Q¬½Þ¨Ï& ΜOÌc‰-l& *ß¼Øj#}Ò§ÍîE¹/S‡.›*¹î]f nX5œÕâ£mÑ‚²IMh™eýÏ–°iò ÂÜì¾0°I{a½¡Fbü“Û¬žº©Võ†AØÀ0r±ôð?ž9Ç>ÇüWB€ÜV~e8\m“ `aM³äIGÌVÁaS‹iC­‡+<à″)¶=Žð{êaÛþóóÅÌ«:xl`Ž£¥\X¥óÝ+“ÈH0Ám®4T]²è%žÊÅSkÉ@‡à'ò²ÁAÍ ŸìKV»:BÏÖÆå§iB¾â Is'?,Üààƒ°k¥¿-°¿02PÁÂnÉÁedfgÍ€Çé1¸p%J'‚wÈ"o O¥ÌÁ4• cþ%¡®Év(ˆ%/EûS‘½ï[›‡í`:s;û}å™t¨¢âó3ñd}ûÉNs¸×»Ä|ffÃ#C7ç±_ŽeÓç°ÛÜ–øTk»íÐwú “[Š­iß°"Fÿ…f’åíªËˆ@¢ŽoôcDCÄ,{'Û­yèø7ÌÛg‹N1}Û¡EÇr´›ù ®»O‰aWÑëêM˜3Szûœ8©ý1q’IzÏBw74)÷¬#p•™qtm#¹%ƒœyšVÿ„ÓÊïÅ,òm‘½^?G®±’ ;N¹CVäÓE¦l¢MZêº-¡MŠ)ÝÔå,Ž³ÙˆÉÖQT'XÕÈM–pej<%†Û¬ kk+ÄMø•¦¦ˆ›Pq¬Š¢0È—5دûÝçi<ΰr£`Ç\)e†µ™Ó»N®~ºu=Ô ‘8ÍñD×±94pÌÍJFf!.¤C:>³|±óX„ÅP°2yÌ[ÿ"fŠ“€Þ" Õ r6&ÂÞ#gò¼bî¤á9~ÇÞs+:ó1õKæ_ ˜õüì@ÆT ÷ᜬ˜¦’‰XTñ¸|ТsÆ”—À0ï²7·x¾¤£5Š¿ê˜›Ä`Ëk¡Ç}Û¼²` 5ðá GKlä;tz`p¬qtvµÙðáù¸»~¹Ý2aϰþã¿|[ËF@EöjKžd]ŸmÇ¡ Ò¿¾uâ:Šu¿à0UJ¼Áô‹Ž»‹Xnfÿú¦'î\ºÁ‡bóèÛEÁ¢âÛ]–êØA;D»üOš9’æíŠGÜòs• /ƒB—ý'õšœv@q Drÿl{“ûlì¾íü¯ošj„ ÀVLþ(³Fwº&Œ e×£žãn|Zñ4>kz=Ä~‚³Ø qÊä™è½3£ÇÏfYìÏoSª¶˜äÙ|iÿo&íüç·v VYOÂsÉL*#©ËHbŸ%#&vöõjˆ×ªÃü»¿˜Žv†fÌð7ÌS«;v(-c Ü(­5‡ìñ·X.Àï×»>Û¹1Ï·“pþŠiÈ3~þ1Ø0ÏNp!’_í ·óó³óVn’ìL»&—YJÞI×¶”Å©ˆlõüã†Ás:ØTm6 & uAyÔtŒÝXê'Œ0ÅÌr©›Â^ØvIo±% š$ÌÅOÅ!9šîNBQuY°:.l— {ŠÀ¤Pn ©)ö·ª…†ÔÒ_°ÓÁôxePo¬^+ς̜òïnœãã¢&õF34—¶+ô!¯ø¨ƒ[ˆFÝÄäÎ ï$a!1%P3´-Êz lødàí âçØ^G p|Á’6@‚ƒ41+a8`!;º{Ô«m½éì‹<2Uöh"­Ã"OÜý¬5$@¨ºtm¿^šHCËàÑpôؤÿÓ­Ù&]À»u•´Kˆi‡ªlbä´T«-âœ>5âfz¢nO®kd<öqª² ¶¿¹§m·éƒmÀT#]Â;OŒ 3¨Ñ>/¨íá$ÂZ0Ì®gwT{lÅ;¾~„ B/GûÄAš¨ž_êÌ&Õs9ÀPn¿f!†4Þ~~׉rÕæ K„¢6m™ F+¶w·æ¹ËLsû ‹ØNä8 §r"ZV×=§ÜÓlŠƒ‰ª· $ŒH‡x9¬š±ûX)ü³N5©9>×72æç$+£0’‹g sÖÕÔð‰’¼ze¬Æ&™àü£Ha…îÓ.Û­:Nå Dùc“,Ú±þò/˜§VCBí(0ǗʾaÛ½‹¡ò—#rþ¥•D<RÍ:þŠø+ýüc*˜qS¨ÿÛeáÞ‹©°(MõeýEÐJ­d_VÙKKׇí üZã~AvaóÞF³J]Lo¬²GeWq`Áð‡,Üå¤?Ï&(ÆìhZÈÇa§Ô§®¿õ3@!´¨÷þ*õ|Â2¾W˜Ó»5GÔëÎJ:ë)2ç8©ªBm k€½á ²‰=G"_«c€ra_ÈìùòN_vÔ»x‰|ì (â8 뻦¿±praâä3C”ÑñLdë¶Ò/˜(ŸAIQ~Úð¼)dà?Kš8äTÉúeQŸ8%m :'[z¥VXKqÙðê.ALó“Ÿö;(Íä!Ö¤ta±Î±{RµÑ¹öÇJ‡&Õ ¶¥¯‹ŒLÝÈÉñþ„Z0›h’OãüVæ}](pŠu‘òµ)ö¡Ä¹è†õò¼Ëîõ؇ÏqÈüÅnmêzút†.ww¯ñè¾Ä5*jŒiah“™bö‘ž(¥û›3i`Á x4†bnSw6‰ÅLJ r"Êk¼:53C¿™ßÓÜÍa¹÷‹YÝ2-%$7ß’÷gµ–%[éœÈÖQ·s¨ãðIC ØÛÞ,Z±e{ a]p÷ &ÆV* •š™ÄÑ ñ™êe Ó©0G¦iVdFx2/­]¹q‰èOtºê]Tl#ÞzïK* ['A3® NÇá;'ÃÛñÜ÷V߬É=žþ§„ó×ëRÖ„“TÞ=S¥Õ.°Î»ÁÚø™²†#\S!MlXF¡ÓÔ-(Fäè€Ëæ(B\Ð[N÷Û…G4P¬\‡ ÑËRòÆ‘¬¡Ï¿bìÕŸÔŒŽ9üGC^ÁkÖŽwj• =iºâíñaG—†œŽN14<Ö‡­Ñš"ÙGú+ÃsSŤË]š6o‡x1Ô¾Á ‡¤<;ÃbÞ%Sàa# lÕáéÇp¬¡0 õU~žŒ*˜liDä¼™ëaVRý…iÃæa9ÍP¢¸3Ü¥ù |ÒäìÁ Œ†ÒßðÍóòíÑ –tC9;´ƒçåIX¤pgQÓ2]P-v¸Átx|íÒË9EšÝï–suÝ0³C÷SB‘ÄÔœ}Š”û‡h¢$L£B³ÿ‘žÝ˜ûÖ“i.2+P™Hg¦á™²wˆãѳ˜6«…€Ã ÿg¦#?Z1?Iür#4VÒ =ÖFÞ $‡³U±8¹™äá…gšQ½§õX¶ºÐ<}¥O‚xÇi:ú3wØÞËÚB`¦:šÝ€Š>à4ïË]ùØ >-1õ¼Ý_ŽÿB¾"[/(Q¢ÖÜq=ižaz“OŽ^<$!+-»øuÏÚL«u¸x­2e ®ÎZý̳âÞvóŸØvVyJÂ~ª×6zïv !/§™öÚÊÓyœ¸¥9“Í×sÏ“ž ò.YÞn«š:±(å¶Ç»û8ˆ³Ï4ìâÈ¢ÎgObñ X¾žó`K1€÷Ó)|ozÇ>ÎÎ_ÎM9å«‘b?jÛEY9â£t¢Nß·º}¿Hˆ§ú{ºÅ¤³XSŽ‘0‚kfyà^>’xÞ%.¢ÖÑ‚¸HO ,`;<Å;†‹ý‹R_^o"‡Õ»¥ÚMjqÀ»Þöq‘&ýo±o¶ ºœ•·±/&ÞØ}XMŠ—Ôµ-û·2Pu"B‚êàÞ5áû—7H¸¤awö–pºM¾©h¬ÅÚÏŒk8½q'â@” ß®–ßÁ8^x.¿_ Y>U‚Ȭ)×hÎÚ‹s¤.œQ—·)NF‡¸àDòÇèÔ”¢[2,yDXLÝØSÛÁ=%xgS­æ³tÇ/Šmf“ª†ÜÈ좇»zÉVÀÙ kê4eþ63#"Z•߉癓îcÙññÁ ·ŽÜ͹RŽ·.¹Rֱž/“àcM;d9hg'”¥@G0A+>} ){¯¶K³QË#©gcóãùa9jú-^þÄ[¾dµÐ‡AÜÌ*Þ©7¬ õ²ÝÛ]¢`gù4à<"Ÿ_ð±xûp¡¼}ûx™¦~Œâ²Iå=LG–}gárâyºˆ*ñÎä…ÄæéÞiô`N±ëãÝ‚S½ß8™€àéEón|:Ib€ù“õ<hzç?‘âÏT‘ŒÅs›sÙ¢í™k’û´w5f5¼^O‰\Χ…\ðoä–xz‘[æéenªqä®{Fš»ò™‰{ß¾suïì{6ïÏö¯g#µï•½ÐÉ÷¤¾ýÅ,œýãp5'¿ûƵ~þÑ΋é"¿£|´Üeˆ(ýnço×ú³¸9z(º‹,0ö"@ø@ uc~ Ó à+ë Ø =BxX­ATqL7têk:–Aƒ£ÎÒk¡sø$Í–‹r#Œ°©¼\”±ºcá äj@ ]—Ç…³ËJ&¨åZ~—VX«»©§©£j‚tÝ@‹DÍ躮ùŸ+éï±S«„#"_è%cx{ ©¸%FS§ Ec.åI­Í–¢ö)UºÖž¦¡Ós’1Ä~vž @ÝNƆUîÅÒlí*’¥µÕ†£q–ü_ÆþðÒõþQ`˜L{…5=–OøV#äRvBw¢è" ¨¥@NmÛpÚŒ’Þ´„-¯ÉN"^ÿ*9PáÙåªF`w£8wN¤gœÇWð3Ç€§I¦È¾Éï‰Ä–M%r¢•YGTö^Š„YÒ 4Ŭ&ÌöªÞôjgQ‚4ÛvɈÅekR•ÜïUO,.HãèܹÛnËÿzC<ÄsxÙ¬ú’½A)o•ʤۣ;bÙÅ n=ð¯èx `ÔÞn8ÛW…3Ó°Ê HºZÏû…„£Â݇§ýÍÚŸÿñD®yê¿Ñ°þ»Öùßm<ņG¥™=Œ!« á7ì*U)p|Ž::¤"ƒ1â1ˆáØÌ‚9àn~H~EVVˆjzÆA)͉ºÄ}…˜wI^‚~c¥‡Û›ŒÞ‰'J‡²µÈƒGÀÆÀ‚BK˯å.¡¸ “O( V_ɲññ…jâ¢'òDp?[t`¯úËê‹ 7¢sê{uÊêRí¥Ù•RD äŒ6º+Í£†EÀãYEªà‘ëÉ+Å@T¼!¸* Ëeœr…Ó@2Bž³’âZUäP&ÁÞ{ÉÄÅ8…hZ¥ä†™Öþñ³SYÒ6û¦É ‰±×Íp ºílYô½ò•/)÷¯Þ«ÖQkQ ³0x¡>©|º½eðrÛw ¦ûåÒ±n(ÄêÙ kˆý8Ô&%—0¡g ¹HPnQ5×ïÃÄ¿bàxÒµQ%Úô ¸[Š÷`.ø?¿1OÑ…‹$üƒð1Éìñ7ÌSI¯å½~š½rçF‰J¹IÅzµ_0~YêÛÅùóËiÖãË¥:@Ñ?˜åÄZ’®jÒäÆJ^æ«{oŸb n'^ŠàuÙ-÷¼3°ÐFÏW䱺¼0ë¡¢0B\Ƕí+ÍQváVä{Ñlñ®ÛÉàu(q§\$l¿g²À®éñÁÌ—óQb–æcd ûìñR.Ým7e;îÔlïò·ZîNÝbW눸æµÍ·íҵ݋6ÜÚ>¤½A†| ÄÄÈ©DbrÈ¥-EJqdm&Sà¢xù^ž\®fK÷ßY¶[r™C­À"KE ”_¸‰°ƒ‘0šù¿!ž*`Ów«çTwç·q†ù_1Çù…ñ“[Kké©õô÷OÌó­?s”þo¼þ$îTVã*Šó7\pžsÎâ¬#ofÒ® .Ö‹@¼ÿx•úl:S†æy”wêðg¢»÷' Ygîjo¹~l~8‰3a?ÀŽ«© ñ!¸TêL§k—Õ+„|ëû ®Ýÿt2Ô3…c%a&ëëx“*¼|)…LK•„È|Ö°ÑsW–‡–N†3M‘žÆÛX¥]ÏË]º÷ºlø‚á]ìaÛ°eÆ«Ú(sŽb‰Êç³ýøÙÂܬ¨ Õv=΄JŽjué¤W}WWŒz®âÍ>xˆ1yà[§÷á™Ð³«ùN(Z…|[q4©I[%,Îõ¬'ÐqS¢?ÑEÇd5¨â20ïïÆ<º¿tEÊgX­—üÞqÐã!)¾H¹1dÈ$ Œù œ¡ŽŒÈ›4‡gfZàáŸè,\š¦tyoÂñà¯&aÂÚpKuåO±q±¯B—Ðq§ºôe“âf“¡+³ž+¼õmíÕhŽºØ•‹bX¯]I¦®ñÀª1º­üŸͦ´2Í)ðH»»3 F)ÕFZ_ÔÀÍgˆ]Ã$±Ë×Ö1‚øVÀÓÆØ£ù›¶¹&ݱoÒ³UÏ¥ÚlÔ‰”¡ ž¶»¯ ÎQë$éjòöS*“®fyVâo vñêʆ‘gÉdŒ×NO§’sU*z8 >ò–½ò¹G"ºí dâÌÈ*—yÕ%JÕÌ´;(ÙöLð€gÛëdm‡ ^û]íóâ¹³ìÎýÍš¯òœ¨Mÿ8)J¡Fö÷ü}:L“Æ­1eŠQYú/Oƒ²BM[¥3ÕyÍŠÄ+{ß¹¢–óÌtò²ÛdëáNÎsBk v~½œXKŽ¥/±ÐAðZÉY_+^å'Õï$ kí uÀúNØmQU±£~ö€õ#,óÖÚAãliYy—sH·œ;2}œŸ EX»=»ÆåTFCŽNxZ¹µÛv¢ˆžtg‘žÄŽZØeaÒy9\}$ýˆØ«§¤hk],™ºëþ]¼«7 ±õûåsSª7Ül‚æ³h …̧|¸á•¯·Ó3CÆÏÅA×Õ1¥ßéí4¤C‡n ü¿,‹’ÄÑnX5*a?ßÅf¥¤o|90§èž«2Õ¨ûòÃæ>9Íáñ5ÿ¼‡-Ü^̲ßÓ•ÞKÕ9k†ÒšžT§1WòcÒIÉ:ô/˜Õ“#Ó½E¾-c&p¾ÈpÕ[݉Ѽ¹‡ƒˆŠ¦+POÍ ¢¢2ê9î·¥‡dYƒ¹5÷ÎÅÈ0Öà2ÔBI^r×@„I$KÑ%…î¡…m·UÝe×¶Cau¯&ÉQ1fîÒ ZÕ™ºR,ªíì|³ˆ¹Â'Ã>]q>.Üæ’˜;3oùApÝ<޹ŠäàØ:»âŽW0#÷Ë>ò3£œNµ Ôò&óvæw›Ëk±»ã4.+ÈŽÓ-ÆÎ] 6P¿-"ÇÊÌ€Ç7û ˲“aû(Š™/*Ûµ‹äFpJ)¾±Msüðâ›í¡Z¿Ó5¿b9ÈK Ü‹‘–±fbرË"3J.ÕbÚx—XÅdÇù(Ùâ·êÀ­WÆ«»œo:¶lv/J72šµA*\ü›V\­Î°Oœ¸œLõìøŠžm½Òì¶·=sÎJØM5nøNÝö!Tsï4’Ø‹ …Œ»Ò ()Q­¦+#³*9’Äh¢ÄRkÞ Êwò¦Ü?O'í „¦æl:¾ê²S8tObe€u &àΪq-[¬=+dTRÒ÷:Žã=¿®ô¯&eÕ)‘Û)Ї>1H&—RƒÜªi,ÔŽý§lËø—Ò¹ ¯™<ÁQÐ>Á}[Bߘ–¦ÌÇ®žbçeÅ@oôí=úäÙ¤„ ó}¡¿¯îãŒe¬•ào bSÒ¤îÕ©iôIŠ[urëó«§qÝÖ'\Í:¾MîT‰´©¡ŒÇ(ãŽÜOpébCÚ“5IMv¼ *Õý°õ°Â2Êôcn[/*a¥jH±m N‹7O¾¤P c°Caý-Óñ—“X§ÙK8mÇú,ÙIÀû1n=SR<˜ŽÐi¥(¹‰›Ç`µgn_'Üý‘¶ûÂl\ãÈ7²Óf§M¥ú 4ö™YÃÜ.û¯dzy%*¸]söæ•È™jNW¨µZÅvžìÏÛ2Û‘~oËÐj󓧺#`æºpý熽1-Í–2LyË:Lɬé-|a;ZÓ¤¥šŸeײQ‰ìÞRuÔòÌÌŒfع74wl+ùÉvÏîÈCÀ±ÉÕ¼s¶—MuäÇæ%ïí=MâÇ)!Ïú(`£9Û±àA°|öÍzc~Ùìiï܇С}Jú+Âb‡$_›ƒ‚[è͸œµb9.‘—4›÷KS^ç½_‚¡Óé8$Ô¦±ÝãC¢.òôþNÄÒ(¹ð¦:Å„­n›Õ âÆÓUlU²ª#°¢DÕ~Ä/±°ç“ÐÌ™ÖMw‰™Á‡êvh1É‹1g;ÈQELQIÊ!kïÕ½xÛ~Wë#b<äΉßO}™–º ZöôQºñY¢XV¬­øÕœšÛ3â‰]*ÛÇL–hÍÁ¢‹${xákæ¨nŒ²MÇq¤M²pOD¬‹Ì^ìxºßÚö:-qÈe˜øÄQ[ÕAáo˜yËŒæw‰>2±8ÆîK’ò›·šh«3‘žµ° @[¶£ú€o;̳‰Ê.ÒÎ’g—0U?µoX5Lqàî*]NÃL TÙÐò9~ÚU7ÈF_jm°ÁG6@Ç/G®£žïüVé¶ý0ª#U‚ñƒ§zS¦Ÿ™ðÙÎX>Ò—„‡n[÷Tx_7Ø,_j´hcXî@ÇfZNš¼”®¹Ðq €%/ßN™–׬¤ìJîã‹’ÐÈóžâV…z\·õ°$¶›ÔìPù%éÿ.Î7¯ÛAêyœìÝqø¤@ð­†ÜhIÁpï?€c—¤oáRR vI'LתΡ ;À‹ôô‡Â&A&9ýª–ÁÝ7Ô’#€-r#l.,ÕLkæ›Ê9uƒÙŽ¶Ú†ˆµhΜ¤ëwâÆŸ¾]ßîŸLáX@ÒD‘Å9ÎB›0’,8o‰µóbí¦léY/Æ/»é2M‘h™ˆéË]×5!&êܧe i A!–tm”XdXÒű:Ε‘“'ê§é/Õ“WaA&÷/\ÒmîÁ8¸8-À:5ÇÚÕ‰Õ¥¦tÂaã«Y½êII`—û†y·eî]b!Lç,ÐF‡¸œ)©Ýê=èDšähâ™'†“@¼´›~JòýYMöÜùþûzÿ¯¢4‹?eŽÛ ÐîV/f£Ž™¤j!¤y†&ò8 ¥ðeÊõó(jNÅÚ²~‚Óv¬”¦Â ”æ(‹†«ÈY—LŽ<®Ÿq\àÒ ý“ž9ÝòÄ9±ö ÜŽiY—ÞD1¼?õ»³D.&&ÅÓ6±3?àËy¬^ÌF@O v¤Âo˜/à¶š=î§ü¨1§Ût0SôÃqû0ËD^Ýï°I$ÍjƒÐO¹pc-k‹Ú©@}’TVëxUÃ1 º š'9ä£XG4&Ж)ÝSö/%Zr%=0ªøy×0†ðÿ[Û_`ÊÂŽÍÓ2œÒ$è§0qùTLéqáTÜ34³3½ÒæpÜ&sJûv'Ã$ˆÀ°S”gjìÛ) R:ÁN™8FÀ5C0f™©0ó|”˜ Å ¨ 3 ¶g'*ܘí€cS!ýJó¦—k¦—¢J:U¦÷ts;Í/öy9†ãÔN…H^ÛÛ´ŽgîÒWnuÏ®=ʰž}VCp~C+iÄôŠÏƒ@xðùyR”™i´£â¥Œ¼j›^ýñ!l>ìWN®¹ÿ©@ËÒ"ÔYŸŠ< që¶ÆX}+oYÝó”f< ætÎô •9FÛc¤`tÊ­ÃëÉÛøƒlÝGú2&Š7e¨¿Mv怲­aËc~Ó‹‘  Sn,Wõ”ÇDÌUj:íy‚ïÏ”WÖ,Ÿz6à3õÂÍÔ~ʵ gÒµ­g¦ æT^lªr°é& X VÎ88“žmîÄ]gæÖ‰’Œ}t¡#øì佞ŠO2Š«‹P(D_91¬ÙZ5?à2•gÐÁ1Äzá;ÿà‹Ü]´Ir s'Ñ,< ÞtÑãi£‘ ‹Ì©X+Þ–1GÕæ'%«S‰.×[Ÿˆ´+¢Ž{y:°*lÓdrѪÄ25œÄf~ÁbÙðƒÈëØ=ýu‹¦AÜÈèé/ÆÉCú–C¸{á?­öÛ.HoÜe¸Øa;{cè÷íSçˆÒ{ïÈ…mº_£;I…Ó¤ÏO¶2}Ú*ùØv ̞ƸMf39nÁëâ ;Ô©…ÍÀÔ©IŒq̘Xð!¿Cfä†Äl!êáÅ¢‘pJSɶlè¼f$0Ý^qÆ{NŒvr\oÃgØÒ¹{ÓA>1'¤Ävö†ƒšN?61&4}UR9®m{ùNya¹LR$ÁÝ×x}øÊÁ^Üã±¹ï¦ÿì=r#­O9ÿŒtU¹4³Î£ÈQ練™+SSóEœºM´~£jœmg·ÒQbî_ŒÓ O¥¡…ÜÔfSî£>0Ç•ËS Óœ3©š ÍLòâ^Bõ¸£MÁå˽±`Z q˜¿Íå÷ 'š[` ¹™8.aÉãTŽaZ¼“ârÄkš…Íšs'b]H[ó_Ö ½˜ky‡Ý•ÝgXN½z1o¯çáM ‡ÃÙ8à2w¢^cìn˜‘[Ùô”¨™ÇV?S!y l¥[ø­ƒœW"4ÌeÉ·ß1µ†?ráQL6‡$þïR:jÀï‹ýãO©ÇG‡yñ,Ô ô*%Íâ->­6í¡šHsçõˆî^¥'>·K†}ޤ=È<½Ÿ®:ñµxXôïC/3¢¯…jwêÑpü¥*9ppS'‹©`*`z§DN˜ÍÖeÏ™¦÷®W²sO8©¨—Vc÷ÇbŠÄ—ÒáèÚËÞmÊ¥.kÆe2æ ¶+œÑ:²È!›†Aë2ã÷•~tu¥*Jä{>…0̸ºýUo±Jà£aïvÕ»lù¡cB|·šÂÓ~];¿ïׯžv{Ä…Gz,[[5T¥:˜™¸æo&áæWê)vÁ2ͽrpŠŠ yqÂÑ”©Þñp2¯ÎOM¦ýl$*?ýî7ÞlÐ1·Àˆ•Ôêw©5¢}7§º¡ÔRÆ8<ߣñi“\ŠtoKr-ûÃøž€=]‡»§¥É·|{.^.ua»k—d"2ŠõÜì®~·-‹¸h›§5!Ú-›Þ2‚m–¸ ®èÇ%%2tÉHKM”_¢ˆéäÐn{§ðjwŶ Šâi·ëd;%Õðê`”WêŽßÛ®¦lm9`61ýÅûÆ—¦¬¦6d|lŸ…fõ¥ºßB³ùý%¦¶ðZ˜ ÊB©Ùí¼ÇùZÙ¸’Ù¨íí4KÑ:ã8«@ãA?eý1–K4i°#ahÈâtHÊÝVîÆ3÷@w…y]ÓO;sËÆÑHÎáÐÿ|Ǥ'$®ûSF'ß‘êýŸßþ'î›–endstream endobj 6 0 obj 20515 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:09:39+10:00 2013-08-12T12:09:39+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/absolute_noncentral.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000020820 00000 n 0000022506 00000 n 0000020761 00000 n 0000020621 00000 n 0000000015 00000 n 0000020600 00000 n 0000020884 00000 n 0000020925 00000 n 0000020954 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<12420228DA652A644C69EC6A55F09B5F><12420228DA652A644C69EC6A55F09B5F>] >> startxref 22756 %%EOF opengv/doc/addons/images/multi_viewpoint.pdf0000664016516101651610000002522613344612246020231 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝœ»r$1rE}~m-¼QøÙZ™²¨X­Á1$ú}ÝsUÕMNhZcp2ÏD¾‘¨ÿzOüžø·ÿ~üzûç¿Ì÷ÿüŸ·¿¾÷ñ«¼ÿ»ÐÿñVŽGmãýßÜúý/ÿòV58Ö{k=V~ÿõ6Ú‘i¼4¥ïŸoÿö6GÏüZÔuЪÏò8ÔªUÆnÕæãP£:µ¨Q=Úz¤ªF5=êr£<þHý½×º}Ñj–òX‹Vý1k´b¢´Ôª¤Ç¤U[-–PWŒkYZËÊåÑ™±§y<ºõ¨Ñ¨£=ú|Ï3ÏÇj¨[}¯ECͱ[uµêj•´˜ªV¥àx/kkÊùQšÖ”Ú#Ošä>EÝ÷š5™nõ×MêÓ/AÈ»ÖþSCyñ§xŠ‹hKK1AJ«ÉðÈC[ìâd£ Ý$íCœkPs­!Kš†P~þf€ªe!R£°Þ}?3RœÄ’ÙÃxXlÒ@½W´JíÞBIbRI›8`<œ–$Z)^`ôïýJ_ÉûXó:ˆŸj¯½<ò¸×^|ï’§™ÿó,šs¸Q>«&¥ñ>Ó­¦eEÓ†Üê¦úÏŒô÷gÕR[—>ùG“}h Z¥ë³TpŸ9¶ª6½Þ›~19j+"byÆH›?šTr—¦´–V‹ØSñ~é/˜™à#ÍUY©ôÕ¯õxœixÆ ²õ:d•ŽXŽp>·ù²/ðí8ª¤r%ÑQ[=DÏ)•ÎX,õÐjÄ‚%ˆâlCîü®åI“¼Ò×KÛlU2ÔBò)#Ìr(šmPí1P²Añù„½të!EU=Ä…Ñ’g™æh²iÓË!“fÑè\6ËÒö3ËÒa³,ìzfìöÐF’øC=šŒTôâõ F”K°Î‘d›útÇʤÖeÅŸ0"Ø(ôumWAå§6K«ÍX»×+Ý9ŠÜë„]¤ê`äŒo07øùÊ–.«Fk’¿)eî#¿Ú|Ç $ܤ¥rû bj!Å Vk‡]5“Ìy6{eß1^Üß¾ºMÒuk°‰Ö`;Y;™ŽÒãU ³qè¸gh $GC·•ìx|~ï_$8øQmŽ[“¾Äø¢dx*z¤O‰s¶–<Ê´ñÝù;ïªO¨.êHS%Igb1ùròþ$”xpúEÚq>Ãg—KRu êX±ìZÌBh‘7ZH­ $v2*7,o¯Ç'F«“6|°º>BÕhކñûïU‰-¥; ¦8–ý….oo±‹„·¹ÁܺdÍrþž—©Ð—5¯¨r g5¾·ä˜OÞ è8L%ÖÓéÃÇzp¶»; ó¯0-”bFšÊLc$vs1çÌÀÆ‹œö‡»=WvQ±‚uì%6 U6 fxW ±tœL- ¤)æIh,þØ„¤ƒœöÃ˶§Ã:šÝa# ˜Ð­xÆ™¬tRƒÄçÑ'³P^â°„™Ó®lîúv/3zPJç„Ù÷¦æÕBüÓÍ£‹SÏby\ÁçéHÕ#˜6s|‡EVL«åv”ã7ÛðL´Þα"èßÜ\–ƒ³›’ŽFqr‡ç¥x0žÅz žëÝ Û/ïø‰³>Áeð÷ãí #íÏ"´¹ƒETü\rɼÑâ$ÒÁ „Hïž0ä¶±ö'xl¹½0ò~LE&xüWÕð!xŒ:Ôkó* òM¤‹uáÀ°ÈŽ•!ò9¨d‰ÒËá±2úÖK~Wôej{¥…ü™^\êiUƒ®ß!¬û¶j£X{½*ó&¥'4TXqà+iic8–üüMgÙ¨ c´Žkyîã†ù»#^©ùFÄ[Z„©3K–¤ŸŠ¼ñG„b´AÈ£Öç¨F ÷q¨Ñ‘bøoݤ«ÿœcÙ?4Ò^¹mÁ½òQ$‚r1köÓÍ8YºB–B¾û$§Uw¨Z‡´‹ƒŒïýd"Ðêï;‚ù©¡^¬æªò&tL¹XQ+¶.R³Åž‹¿Ÿ4i$8ê:lñ ‘ºxÂôðó“V²ŒÈv·ŸšH±`‡ž;¡_ÅCiäàë•Ã<—ãq:ùÓ­™‘’c9 ùÔæuWx@Ù—Ñ*HWõqMyéˆâ! I­ Ô½öYÑNz`?×îC=Š-oqމŬ\ȵhÌ1³#Vù\y¨'æó 3«=Ëg—Ú3"4ûF 4uu‡†ºhrYÊsÙ^Vã°ËŸàe¡±Š@lŸ˜¯³}µ¢.+§|Ç€ùu6 ?=ÕrÞ«jŽU¼ 0Úˆ0wŒßñ2È+É9†Ùä!ˆQJÍ _UØuÂíÆ|ÞMÐlÚJþ(ÏM¾#D4ÇŒ×ýh¿Åh==£ -‰³6¢M¬ï;æZß7wÚ&ÄÞv‡³>$þ'¥~œI¥K+ÜÆ¡„Lþ„úÿÝùÂïý§U8²Žä½xÓ?3à‹Z˜X%Rnòªf2Åu\˜‰o]TnEbÄ<·ÄdòYíB7Å"Ì8wÈÑrµc7§Ô@±ŒúhÕCƒÀ&-'bŸIj‰“ØX\}È…§¸0²þÒ,€´`¿?b ‚ÁT-¶ôÓ*ŒZjÕr: pÅ÷.Z¾`v!Ѳ^;[Ècñ”ÒëÝTY(KEćg8ÂxxNÖ@[¼&;¡ZRFÉ„z=Ü»¢GBdèÒ‚˜šDÀÙö”™9 # &FõuÏ)”ªŸøÖÕpÅ?÷Q˜.›Ô-V±[̡պÇFžx£½Çœ›Ö‘Ö ZròŲÛyº@M J"K0¾ä…ùÈI5Æ×Èëmä›Sv©Ñÿ”]¢jÉùz¡"‚…ð„M¶ äÕB*l¹GBéL´Ÿ Çq¬ˆéXd.Ä 0Ýñ†¥î»éza´z­VˆÏÑ9‚z,I'Ûã$ÝiÉ­í%ÀßÍ™ÑiÇ»^ðÞA«O-†C|XÆ,önÙ=NŒ–˜ÜÃ}Á L2x…sï9 „žÎh .[l‡Åöç)¶'æp SÜšà‹bÀ“ž‹ûæpr^ }À†×k,Ñ—Òl†~)Ú/ óôþZ!W¨)HïkS…ÀGt^Ë9NÁf5:è°÷£8c0ÝC1àŠ¤6+|¼ ã4”¦ˆ,YJ¾çð” ežàÌrc†s½šÓ±F+ÕIãkÙÎ >ŸÃ‹Ê™ÉyÔ4Â,R Ë~Å@àwÂ5Å[žâ”&: é/%-²¢¯Ý*9iÒá¤õyáð3#ý=n2Í$GÜ3ÉsÏü/ùíÛ¨>²¹Õ¸Î„rON\&iú½ŸÛ4¨r„ýÖÒh¤/Kïèµ_7fa "EâðšßJ¦EÞM!!4M«oýê"q[žÚ@öê%°óŠ¬Ë½ ‰LÅ-cáC?ù’¯d¿Ñª·»ùrÄPð(+Fþû…kQ ‹þ¦HJrãðCCÅY(NJÞEâæAÇjÉ!0ý%$ Wb€÷œ¤%G4âL^ ´ùÞ­ HYå"P¶üÐH{é…žIdÈ.>j2r w[ç)qÅŒíréexS~ï׸ èvÚ+ñ€×þSC½ør½å’"¡g¹rBA¦Ó©äªøÚé§+éØÞŸäd²úÈuʦYËŽ‚î&Nî¿ "ö! µä<„üV°y­…6Š¡Xü†dŽ:¶XËÀÜ=5ù²%4®hf×=Ð “ØÞÔ)†¬æ+²(2„2*8wgûZØ›V7ù`±6ò‰!o Iðõüº`õ ´Á›Ý˜Ï#.¬æ¶²0%ó“ÃgÙÁ”;üÙcRys{Õ¬ª˜ðÑ™ŠUV¸»„øìK*¿Øµ<;TûÅ“#ôõ¸8£ .Ù±>­ÉnÿBG$®²[Ÿ}¸¤ÌV¿›øê®½ òJqNA—0*Eìʽ«!œ):1ŸW»+a†Üê9e‡¥u\¢q¶ùŽ$‡U»â÷[…#0ȹä".øöê¾!îÅ} îlÀ{ %àÊ‚¾.¡+Rÿ¢„su«Œ –·&Ñ"(M(Lú­¿<¥d9ÁqLó5ºû¡_T‚Üöd@YI·žÁo ybäù;¦a["‰.ð†È¨®([É\!NëˆL%™ÉyŸäToM#öºÈ_°ÈÈì Žô1>—Îþ†‰ bŠ#é"ÓÆœžBñH¡ò³¦ì1©%!¸7féjØiš†O7/ðC›V ÔæSIš'Œ‹"¥‡UçûÚBA™ñœ¸‡IÁY÷’ŠÔD2¹±d=¸¶X´XVŠŽV9ÏRZ Ѽߘ´Ä¤Ü QrPq}bÌQbbCF辕¾á¶/pž0¾¬m”dF¨Ãém’põB-ÎSADŽÁ$>/t(\¢iößàÞÄ,÷ï=L$ã9‰yÂ:€§}aXÎpÚ&SPàxœ[#HÐíÀìñ%™²¬ê}Ëm ¹½à}þ„=G~’üWÝ@ˆç8ÝÇÅÒ„ F#ƒ(ûv-S¤²ÈÚ¸Kô¶¤>‘½6l’6â¤ÚØi$ѹVàÃ×^ ã}S¸Žò´»}v”p4+¸½3ÂôX+áƒæ&rRKrÃc3ËI\j .ËvHʽ‡½çoTÀX´‚‹óLW•‹0¥»Rð$ÌÎØ?¦tû`eÊpâñ¢Œ|ð Ü& !l.aŠ”`:nÂ÷ùL™rŒMêM™ÃœrSæ‚/Ê\˜ LSÏvSæÜÄM™W*8–¸g|ÿf’ä€4zŠlò¯‘\2Y¬ªðŒ¦e»`üð7üYO?»äî~Á1>ÍOLxÍî®@xAãsôVó=ÿÕâ\Þîýºüÿ¿ åþ´ýâMü‰{êVŽêS†Ã¸'Ó˜ß;í¥+w`\ܳÜz’L_º1ê¢4®n8¦ Ç‰Á|Ñcи£Ï×üx»Öp58×|Ýüù§îìO>µÈAPƒN1¹†¯Qƒ¾5¤ú< [[v N%äžpÃr½f$éïQytpÁž‚Ñ“/´®z ‰:§Ø°zœ‹8[œ‹³;„Œª“¨4à²É7„¡àÌÙø—ç×EcçâkßéŠÚRñ„ˆY¿0 ùÓñÔ†Ž*j8ÎMßÿz[•;ñ³ =|‹D×(«9Š$(ìä(*$¾vZöÚ¸&‰²#úLJ XmN…FßÿC}4•bRY£,—W‚é¾èJ˜µ6·¸¼•ë9Í"x—Ö9œ¬f9 v±Ë¨É×À•Ú$J j*qù¥ -›[*…|jÀSŒ p7«€GpßÁú<|12ȰéÉíY€räNÌô ›_ !ÇÕ‚"ãÄ TS|3¸Š•ä-¿?4¨¾ cÍ7W7ŒŸn :1yùÉ —iƒì’F\ %5#Ghû™íìç ÏÚùú¬æ“«º/)Fnù¹æ,ËàôXñ²(1eqùŒ+&#”W~¯NtP¸4J‘·r½Z©?LýMÔKÚ¿SMÏ(5lIƒîSSPà%go®ºÄÌðŒdˆY`^{ ` dÈŽC {“Qúh¸{ŽJĶ{Ĭ¾‹4 §ääËfËUŠ5ŽØϬ˜#ÕPvÀÌ‘B>€ÙeZ3ŠÜ ®¶R‰òGÚ%n8E^æÆè°–ïg ÖbT©_hܘº F*e¾:Úßa®^TøP?t|b ·¦»ÐŠŠ¬¥ùQJ=óWÌ“Hs™¤#•Bû’¹´91$±à%’Ì<]ÁíØoʘµÍHTê„u¦ƒ¬ŽKðHñÑbW³ðbñ¦ï‚èÀz)È‚RXNòGOp0!D^DA!•®…—Ì—ã$„•ÂQOð#^ûýûXl1Á¨!ñ‡o³m&oê(qìÝ5¬ƒ›ß2îcwÐ<ž2”xmâZD¦ŽÐT3… Wb‘~°wUXÎÕÂuä9äü°Œ”åÞ‘3íaÏ<æu6˺% 龜¦ý#üIŽÇõ.NÑ&¿èi8UÿùŒ±¬q£˜)Çùb÷©«Û$îaŸdPl+ÝÇ{ñÐâÆpÂæHngl ÊÉäçz¿cΩˆBªß1V.m›:ƒ²·í™·xì´õJ§pfØJ¦°MLa¶ÉÝ©œ™9Ÿ7?dÐ,ó¼€<ÜrŒÐn 9(Œ³Õš[Éô–I˜‰˜·Xe3`+x!''¬èלï~zµb…¸¹Æ´RxgãÔ]ø¦Øæô¦$kõ'XF̹êCž¶)uÈ~w*D°qäÛ4 ӌȒÄx\…Q)š|ãÙ©9ÑJj_;wÞa‡óF=']kGrD% ¾ Ïžl™zN.;î<+â–Õ…+OM$;—4Q!¼~‘›4Q· ícFõM§´(:8ÅÜÉ“gà _ͬ+Ìç¹5§…qÞÊpi1B>n†{˜&c†7ar†Qx»3JÀ<¼#ñWχ1ñèxA6Þ›yÊ‹æ•Ul£Qèí¢Ý´𞇇¡ó.ãjßv½®¯?!¯{}%{¼`Žýd®­á÷¥¿Ãœ½ôsÇ=ò…™QÔâ^-ü= Ûæ ¦·xjè8v}Á¼Hõ'̵ TF6ßÂ_1Ô€¡¸ôóD_4u*ÅBVØ'aJø$iñWpŠÇ¨ n.&æ¡N‹“Y~@â8ˆÇ)Xz{ªÕ~©Ò÷•:›‚ÎýAÝRÉ“ ŠýÔ*¨aÅ0/ð#È^ÊSrà9ðb ‹=v!8¥5cÒ8ýîëjr˼OŸÇ{Qçñ/çë!nw™˜$Ó÷F;ÅÃËÅ´{ÂÞXs5ïÕ‚:Ú#„ý0iüPÊ`'‚øua¶½‹£Îï_Ó %l4O{ß©ï“]¯âB TþÓwª¸»€ï÷lŒË Å~fžfìšë; âWI@áÔ)_0×\_vñ´ÂÑürÆõ*v;N m¸›ËÏ#_ûú†¹zýí­ÍòQŸîJaaº“BÎ3½ kWèP‹ß:Và‰Â;V'¶T€@_¤ÔZâ•æ'5wÈ!Ä´µâÆI&¼´æ©W§][<*®5m0£œ»ï`œòO'£%Ví~xÈÉ—ÂSJíyc>ìhÝ›Nvå2ñ$1\ºSmYTk¶É¦G£Ð÷nÐÂâå(KÑA…½ÃYØG§ÍzÉh Ï< O·‹/˜Üÿˆ €m„ðÓ:ÃÞaÛˆ[mÁ¾ìu´Œ¡|7«äê't³ÅÚ"h2·!×Ýe–Ë >¡zpDih &¿4L$Bt;Öœ÷Ë„ “æò3skvjô 1v©S©ÕÅ ¿Ã\j7#ÞÞjúûÕ)xtÈߘšâŃ¥·ö¯˜'yþ ¶@3è'tï¯' Öc [¥-ða ‚ð.*xß±T˜~_¹¹«náW •÷µ™b„µ¢"¶ø²-’üIpµ \Òñâ»>R&äÃ\Ï-L0 ‡Ù}·wRÄÌjØì›ðÌî(Œ#x4‘{È$ûÖÈgç´ÿ°y¬<-÷ñëXÎE ,ñhAôPV5´5×Í–‹Â z[‘•¸P¼ÓCÊ­.¡å?3–8]Vó2ÏÞgÅG"æû×ÓÄî[KEDiä‰àÙÍ¢ Ò•Þ•êBJ÷Æð£Øê‹§8½¬;û­Uá)™ͯÍËèÁÀ8@¡/Gw}TÅr“éäÝ8Sâtóò‡'¬lK„5$5­=ŠËd«Ý"Þf'LdÇën‘\$h}¹ú5à Lxèûµ‚î-<Ìí{ìªÃƱÆ*Ù¼!ÌDÓ~2Dø2ϘP’x‡+‡¯_…TÖ‘¼p\[r+€u[£uù¦ÆgÙY;‰éâT—£âÝû´Z¤xjР[Ë&¾XQü*z׊#»ÈÊ׊¼Ã[ͦ¨@(|µb þˆJÙç<ªh{à(ðò [LQý2Í{¤>÷}iH1ޤ*üã7¿f«Ú0 ‚CɶAµ`«Þ¸{Ý ±ºæ«@ÀĨ¹æ Ó­.LãC@€akŽ˜ÎÆ.šì™ì½GM0a= Œ‡Þ’{Œý¬X›^öc]ÌÕàùÝÙ_œ޼uÁŒD@áý*¡.°¨ÐyŒ€q ðfC¬ð®}Öýuà"Ö' ·Á èÄÂŽt–5ŸÓ›AøüÅ 5bé­Gè˜Ã¦Ã›¬ãvd}^𰽓òs¹³Éub\ae˜,Há¼ v«¡ˆŠ½=¢Ã5vƒ ›Sm•J´‹"Vqe`(Y;^0˜‰jTêQ˜†5†-aˆr–l ‰¼03Q ÇÐõx"»0õ„-þ ÂS‹ÛÀå8BšÒì×Å&¬Ö°‹u'¿²3ÜC ùZ6ân‹÷Šo]ñ‰ï¹ö.J¨);†Ú¿ŸfÓbˆêË +Œº‚ˆJæ#ФoF,1Ï]KÉõRοŴýÁ ë¾X•¹Ò(áÀRöc­VLÛuzÀ$W`¬,—kòªë…fìã0\/>¥€«QðÎá¡ÒÜP[^S¼20iØh÷ƒ1ƪ›Çrß#–ÈJ‰%\•v·ˆë /Òœßý ó¾·I•·dÖU§ÓÐ\·õÅ«ÀÑíàû•)Þ—ó¦~ºW0ߥts”©òn™‹Úý"-aOüüxWñ7_ºqù›|°-ññ‡ <Fúm°B}?1#çBŽ»g×/¶ì¢ÀÁ3[Š‘kŸÏè¥Å+¶¸èñÞзф„ãiy¾ë÷i_°á·fÆ_9>Æ@mjkð™’îü°ôƒ–Œ›‚‰ùªã†µ°T¢C Hiˆ3bó.ÇksðE”I{†ÌžxéU¹%íË>#þú⻈* ¾1 Sãƒ\u5vá/IQ—|peØý¦w‚Õ´‚J=lß•ñAH½QÁÄ×  øÛ'l²&/âjÕç$×å%sr~_B%Ó!EžÓr«O×a_×h~ÃܽZuøÿ4òÆÔ…M»zàF¹ÜÄkæhqÄ[ÞÄ-ÔŸÁáMøʯS‹ŸG rË8âRƬvª²è€ã+½Ùó V?q“ʇâ0ª¤6¸¥ïͱqåeZÑ#ÅŸÓ&ƒô ¾ÕáÊW„œ~2hv ý⭌¥u¶iavõç¶"q~én‘fÀ)¦ˆ‹=ûóà•Ïôœqô(7_ªûóeçIW;]ÏgÏ…~ñg9Ô'žFñ9ŒiõvìDƒöÝC{9€˜UÆ‹Ÿ»϶³e½£R;¹‡~iIö•AqL%â´¸™•‰~ÿzžÖädÓù,l@KþÚ¨Ýáza>o Bä«»µåRmpë9ü!Ìw?òàÙ Á¶8ÍPÞƒ y´„òæ³ÕŸ@ˆ£+£yvØC÷­|jªIÏü|)w瘜Ǻ‡ ð§Ë‚‚ć±œ þ¶ê W¿œ]“vŠofdg›ø@oª·°ôÙB/ØÖÏ[róG!­Ä×/pÆÿ r¼®~Ý5BZ& ÕPÿ6q3^øt¨v„ノcM9" Yq½™r;í0T:ÚvÎÅ9T;„+蜇»å8‰y ©{:L×ÜW§ ó¬Žu«wˆ¼?‹âîÁñÕ#¥gí¨DŽT‹³æfÐÉ´}Ö~§³UÍÀoòšä͇¥ÆUZ~Åw¸ƒ¨œ_d³†=Ý3e ˉÑZNÃ:f8ûˆHpÓt±d¥š-1æ §j:ÈÒüß!²=[pšÙþ¤5ÕàÕòrPéïÁM 1 ¥ÀÝiqþ›T˜§<á#Œ¹{l 7 0HäõH5{ÜÞt‘éq„rœñ5Òþæ ßcá’Õ<`-½^Ün´ý ¼äSæýY˜­¥6æó›ÞúÇuýv¾¸å’ÏŸ¾0ä°R>|øÍßµ†u~ç„m9\"vµð§¤Ö= ï9>ÞN ÎA=Éøðœ1Ç Ûƒó*®{•×_öñ+üÿÜSqøgïî_ßþ¸—ëendstream endobj 6 0 obj 8316 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T16:25:07+10:00 2013-08-12T16:25:07+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/multi_viewpoint.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000008620 00000 n 0000010302 00000 n 0000008561 00000 n 0000008421 00000 n 0000000015 00000 n 0000008401 00000 n 0000008684 00000 n 0000008725 00000 n 0000008754 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<6E8635154C679C4EDEFD281566D5DEDC><6E8635154C679C4EDEFD281566D5DEDC>] >> startxref 10548 %%EOF opengv/doc/addons/images/triangulation_central.dia0000664016516101651610000000370613344612246021346 0ustar dimadima‹í\ËrÛ6Ýû+4Ê""Þ@93é4«L;“¤k %Á2ŠÔP´wÑo/´­©E2’KMÇ4|/žspqqÉÎÃνJ–A »xÝŽŠ&ñ4ˆfÃî_ß?¿Ý×W¦ÿ^ÿ%þ¼£#Zšï†ÝÛ4]¼ï÷@ø¸ôÓ8ap–ªÿ¯†~_7êw¯¯:US?õ͵쪟¦I0¾KU'òçjØû“³$¾‹¦]×*k7‰Ã8éÜûá°ûæÆ~ºýÌLÍÎÛ ¦Æ‰ò›öôGÊ2¦*Ù4;_ÄË@7I[M ì˜WÚd­–ºQ4»~óE¥©JÞ¸ne_ìåu¶ÐQ:÷“YmûÒóºÉ@€bi> Š=ÄñÓ¼ïnܬ»°YwI³î‚åh'iâé¶Ëq‡Êœ×4¹Såý,'~¨!¶kX°¼õ› Mã=ý¿ñÃå!p—Ÿw,{gI0ÝMÞµV‚iz;úYÓt9ë5Y¿–Á8Ty½¢´2ó՘߼;VÁ_~ýD48k…KÄT(ªèñKÄì.˜ªå˜­·)°t›5ëï›õÍv‡NŒ»´±`[¡ÿ¨’Ìü§—¥º“ÝàLq:þ$ [™“xü·š¤Ù`¿¥~4õ“iç]çKéßzDtL‡Ý?½õÙÚŸ¶¦…pkºñ3¦‚ö ”nζ†¹7=$z~4 Õ³.…èÀˆt@@DÆ/Ó_ËyžÄQ4RÑÔŽæè1æ4cRÝE^®;ÑÝ|²ØìEw1ªW5Z¦¡Ú´¬´¿¬ß{L»‹Xå‘OEÒ÷Zß}çQPÓn¨@¢Gô8"aYÇÕ µüAæ`M÷Êt‘Ól9`CU€ 5„6*¤qõ׆€"{PJÒÚÐ!pÓÝ"ÈJ Dç„8=È‘Ÿ$ñC1àÊRöÙô(TÑ,½Ý¾‘OA¡è©.lèyЇjhƒ/G£ç̲†1@š-&@ Š3ÑhÓsjz…[μV΋Zj´ ¨GÍBƒ .¬¡g´Î@äúÈÛuæÕr†VÀNü×L&ïA¸Gá@!r¤!×ÏšœAæ†èUϰF÷òüö빞ܳs$Ðòò xɪËÕœ n7B0¢¢y¥è!<"acÉ ûs#êÈO¶ËØ«¥ ¯‚.M°CX ö¤ÉgQÉ uËm€-ûÉ¢»dú×î’^-UDTáõ/-0Æq½¤ <Ð^%¡öœr¯‰s~ÀÚ‚5£M;D˘×ÊYY,Fj^^˜'¡Ù|`ˆ‘9™Ã b⦂1²›1šÆ–YȤ±ÛRËʽ¬ü= ƒÅ2÷ ³Š3sj6ì`^37 s~Ì6I“À,ˆ²P¡šk¸&Ñv™]µÃ³ŽöÞòÓÌߪ`v›î´/W>“’«í8N¦*Ù?è¹$Òƒ•-k"}{ö‹ŠóÕÌÑ?¬€1XX좚 ƒ!Ú ä»*zx„òú—²œ!æW™8Ë_“ì;ßÕÏtð 'Ñcq˜“èÕŠ çÆËÓþ¿öx‚ˆ²“ŸšùØSm·Ñ¦¨xÔ–'¯µÛ¨f¾)(dÞQýWTJGiž's½sãσðqØýÌÕ²ó‡zè|ç~ÔíØZaWh!pfl‹wŸâpº ñ㻳¥Ý¹õÀBýb™–rÂOó¹ŽÆÃYÆ×¦z–qä‡Á,š«ü›û"ê%·üñ8~ÜÛ.G«¸y:¹Â,ܦµ­wÑÊa“<0ÉpL_/B£Þ¶"Õ¤HᲕ©K”©“«Oˆiz pTïNÔx¡Ú](ã6|Õ¸¿yZ ?¶úÔ¨>å²6qÚÜ·âTBœ>©•mþO.ö!Än·LM4«µÚGÁ²*gLÈ@û¥TôRV¬lîGý3Ú¿õÏ`ÎCfzˆ<-¢»[jÙš ¹zF”Sc´2f^ú0Ø$GËbÌy[ÝÈýYõÙsCð—g™›¢¡MÌ7 \»„íã[š0¨ÞýZæ‡ 0ĆãÒÖŠŸ<ôµ†M)僲ÖxhU,Ûx¨Âc^EÙ3v5Á¨î²gby„„q³gRÉÒqo êy{Œ¹ç%<«–!—w¤•*”´‘Cµ‘ƒ¨ r`±„óšCæ ¿¤‰{ Íðç8¤màÐpà‹ÉÚ"‡MEk#‡ %êäb@Ä@¶¨zõJÔ“#“Ò ½˜Cû˜.ƒç¯P“fês¢Ô7•7/Úô$M¿ÅwI ’רKE@l3¼¨KÈ«à”ܦ ¤îSòìdážË®ò’.“·­45r2ž‹ÅVš.QšN®9Õ,›y«õÅfΉF£,̦¬OygãÿGY‚æíŒRÊ©'¡Õ¾“ËÁa›ÿ½DIBHqa Á5«q©Uleɳ/$ã—+µšÔˆ&展¥K”%\…,Ù­¯Y“lÙ*ƒ.TÊ^Hè±6Tje©ˆmÂû5‰T¡IF-xÝq’Iu3f+y$v¯ëºŒÍ[+HÍÒ& [Aú¥‚ä¾·oÙ¿¾Z{ ÿõÕ"1º®gopengv/doc/addons/images/nonoverlapping.eps0000664016516101651610000005727513344612246020063 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/nonoverlapping.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 17:41:41 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 1248 632 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale 7.265770 -42.514400 translate %%EndProlog 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 8.719199 33.691291 m 15.820121 40.781109 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 22.502662 33.765953 m 16.176938 40.773747 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 22.468149 25.870395 m 16.396151 20.664405 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 8.740989 25.821394 m 15.983011 20.646106 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 12.956206 29.768438 m 36.226994 33.818062 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 27.079236 29.892609 m 36.244364 33.761191 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 18.307211 29.752772 m -5.362491 26.129728 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 4.168667 29.634295 m -5.364307 26.180905 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 4.598305 29.704152 m 12.467695 29.737648 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 4.987562 29.455806 m 4.486502 29.703676 l 4.985434 29.955802 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 12.078438 29.985994 m 12.579498 29.738124 l 12.080566 29.485998 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 8.740665 25.821442 m 12.973195 22.793161 l s [] 0 sd 0 slj 0 slc n 13.278173 22.574956 m 13.017006 23.069215 l 12.973195 22.793161 l 12.726066 22.662577 l ef n 13.278173 22.574956 m 13.017006 23.069215 l 12.973195 22.793161 l 12.726066 22.662577 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 4.168667 29.634295 m -0.140125 28.073404 l s [] 0 sd 0 slj 0 slc n -0.492703 27.945680 m 0.062551 27.880926 l -0.140125 28.073404 l -0.107748 28.351031 l ef n -0.492703 27.945680 m 0.062551 27.880926 l -0.140125 28.073404 l -0.107748 28.351031 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 12.955534 29.768728 m 17.491333 30.565206 l s [] 0 sd 0 slj 0 slc n 17.860681 30.630063 m 17.324978 30.789820 l 17.491333 30.565206 l 17.411454 30.297355 l ef n 17.860681 30.630063 m 17.324978 30.789820 l 17.491333 30.565206 l 17.411454 30.297355 l cp s 0.000000 0.000000 0.000000 srgb 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 22.467712 25.871477 m 18.785298 22.741097 l s [] 0 sd 0 slj 0 slc n 18.499584 22.498214 m 19.042458 22.631581 l 18.785298 22.741097 l 18.718615 23.012534 l ef n 18.499584 22.498214 m 19.042458 22.631581 l 18.785298 22.741097 l 18.718615 23.012534 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 22.499879 33.769065 m 19.496460 37.096818 l s [] 0 sd 0 slj 0 slc n 19.245209 37.375202 m 19.394622 36.836522 l 19.496460 37.096818 l 19.765800 37.171524 l ef n 19.245209 37.375202 m 19.394622 36.836522 l 19.496460 37.096818 l 19.765800 37.171524 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.079623 29.891701 m 31.316502 31.661287 l s [] 0 sd 0 slj 0 slc n 31.662533 31.805811 m 31.104809 31.843800 l 31.316502 31.661287 l 31.297508 31.382424 l ef n 31.662533 31.805811 m 31.104809 31.843800 l 31.316502 31.661287 l 31.297508 31.382424 l cp s 0.000000 0.000000 0.000000 srgb 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 8.514452 26.223007 m 8.519208 33.227293 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 8.764715 26.611033 m 8.514376 26.111203 l 8.264716 26.611373 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 8.268945 32.839267 m 8.519284 33.339097 l 8.768944 32.838927 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 18.301064 29.753051 m 12.694340 28.921793 l s [] 0 sd 0 slj 0 slc n 12.323395 28.866797 m 12.854653 28.692829 l 12.694340 28.921793 l 12.781324 29.187423 l ef n 12.323395 28.866797 m 12.854653 28.692829 l 12.694340 28.921793 l 12.781324 29.187423 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 8.719201 33.691291 m 11.925207 36.892249 l s [] 0 sd 0 slj 0 slc n 12.190581 37.157205 m 11.660112 36.980847 l 11.925207 36.892249 l 12.013386 36.627015 l ef n 12.190581 37.157205 m 11.660112 36.980847 l 11.925207 36.892249 l 12.013386 36.627015 l cp s 0.000000 0.000000 0.000000 srgb 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.498039 0.498039 0.498039 srgb n -5.610280 26.091800 0.212500 0.212500 0 360 ellipse f n -5.610280 26.091800 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n -5.610280 26.091800 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 36.485800 33.863100 0.212500 0.212500 0 360 ellipse f n 36.485800 33.863100 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 36.485800 33.863100 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 16.196700 20.493400 0.212500 0.212500 0 360 ellipse f n 16.196700 20.493400 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 16.196700 20.493400 0.212500 0.212500 0 360 ellipse cp s 0.678431 0.678431 0.678431 srgb gsave 15.771500 21.739800 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 16.584000 21.934800 translate 0.035278 -0.035278 scale start_ol 2624 960 moveto 2624 0 lineto 2048 0 lineto 2048 960 lineto 128 960 lineto 128 1376 lineto 2229 4288 lineto 2624 4288 lineto 2624 1408 lineto 3200 1408 lineto 3200 960 lineto 2624 960 lineto 2048 3539 moveto 2032 3539 lineto 488 1408 lineto 2048 1408 lineto 2048 3539 lineto end_ol grestore gsave 35.395600 34.797700 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 36.208100 34.992700 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave -7.265770 26.069400 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave -6.453270 26.264400 translate 0.035278 -0.035278 scale start_ol 3008 1168 moveto 3008 877 2906 648 conicto 2805 419 2612 260 conicto 2420 102 2139 19 conicto 1858 -64 1499 -64 conicto 1184 -64 888 -26 conicto 593 12 355 71 conicto 320 960 lineto 531 960 lineto 674 363 lineto 732 332 824 300 conicto 917 268 1023 244 conicto 1130 221 1243 206 conicto 1357 192 1453 192 conicto 1749 192 1939 266 conicto 2129 340 2239 474 conicto 2349 608 2390 793 conicto 2432 978 2432 1197 conicto 2432 1448 2362 1614 conicto 2293 1780 2171 1881 conicto 2050 1983 1887 2030 conicto 1725 2077 1539 2086 conicto 1088 2112 lineto 1088 2368 lineto 1541 2397 lineto 1898 2417 2069 2625 conicto 2240 2833 2240 3256 conicto 2240 3468 2196 3626 conicto 2153 3784 2060 3888 conicto 1968 3992 1818 4044 conicto 1669 4096 1455 4096 conicto 1358 4096 1260 4081 conicto 1163 4067 1073 4042 conicto 983 4018 906 3987 conicto 829 3956 772 3924 conicto 660 3392 lineto 448 3392 lineto 448 4215 lineto 559 4244 670 4269 conicto 782 4295 903 4312 conicto 1024 4330 1157 4341 conicto 1291 4352 1447 4352 conicto 2119 4352 2467 4091 conicto 2816 3830 2816 3289 conicto 2816 3086 2762 2910 conicto 2709 2735 2595 2600 conicto 2482 2465 2307 2373 conicto 2133 2281 1894 2246 conicto 2467 2179 2737 1912 conicto 3008 1645 3008 1168 conicto end_ol grestore gsave 15.362500 42.131900 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 16.175000 42.326900 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.498039 0.498039 0.498039 srgb n 16.004300 40.965000 0.212500 0.212500 0 360 ellipse f n 16.004300 40.965000 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 16.004300 40.965000 0.212500 0.212500 0 360 ellipse cp s 0.000000 0.000000 0.000000 srgb gsave 6.952130 29.192500 translate 0.035278 -0.035278 scale start_ol 4051 3625 moveto 4051 3767 3824 3984 conicto 3597 4201 3597 4430 conicto 3597 4604 3705 4702 conicto 3813 4800 3997 4800 conicto 4245 4800 4423 4609 conicto 4602 4419 4602 4159 conicto 4602 3854 4413 3381 conicto 4224 2908 3943 2505 conicto 3111 1331 2441 569 conicto 1772 -192 1566 -192 conicto 1469 -192 1469 189 conicto 1469 656 1393 1651 conicto 1318 2647 1231 3212 conicto 1123 3962 993 4179 conicto 864 4397 551 4397 conicto 346 4397 227 4386 conicto 227 4528 lineto 605 4593 886 4647 conicto 1167 4702 1275 4734 conicto 1383 4767 1469 4783 conicto 1555 4800 1642 4800 conicto 1815 4800 1993 3516 conicto 2171 2233 2236 765 conicto 2571 1113 lineto 3143 1722 3597 2488 conicto 4051 3255 4051 3625 conicto end_ol grestore gsave 7.544069 29.192500 translate 0.035278 -0.035278 scale start_ol 961 4414 moveto 605 4414 lineto 583 4570 lineto 2247 4800 2268 4800 conicto 2322 4800 2322 4758 conicto 1977 3589 lineto 2452 4243 2873 4521 conicto 3295 4800 3824 4800 conicto 4396 4800 4731 4434 conicto 5066 4069 5066 3437 conicto 5066 2140 4034 1006 conicto 3003 -128 1826 -128 conicto 1469 -128 1113 77 conicto 713 -1429 713 -1747 conicto 713 -2077 1404 -2077 conicto 1404 -2240 lineto -810 -2240 lineto -810 -2066 lineto -670 -2066 -583 -2049 conicto -497 -2033 -410 -1983 conicto -324 -1934 -281 -1874 conicto -238 -1815 -173 -1678 conicto -108 -1542 -70 -1405 conicto -32 -1269 32 -1006 conicto 97 -744 156 -487 conicto 216 -231 324 190 conicto 432 611 540 1026 conicto 1307 3955 1307 4119 conicto 1307 4217 1188 4315 conicto 1069 4414 961 4414 conicto 4094 3415 moveto 4094 4352 3381 4352 conicto 2981 4352 2576 3997 conicto 2171 3643 1966 3109 conicto 1728 2498 1496 1637 conicto 1264 777 1264 505 conicto 1264 330 1409 215 conicto 1555 101 1782 101 conicto 2430 101 2986 690 conicto 3543 1279 3818 2030 conicto 4094 2782 4094 3415 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 8.527300 25.974100 0.212500 0.212500 0 360 ellipse f n 8.527300 25.974100 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 8.527300 25.974100 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 0.000000 1.000000 srgb n 8.535020 33.507400 0.212500 0.212500 0 360 ellipse f n 8.535020 33.507400 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 8.535020 33.507400 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 1.000000 0.647059 0.000000 srgb n 12.697400 29.723400 0.212500 0.212500 0 360 ellipse f n 12.697400 29.723400 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 12.697400 29.723400 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 1.000000 0.000000 srgb n 4.414640 29.723400 0.212500 0.212500 0 360 ellipse f n 4.414640 29.723400 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 4.414640 29.723400 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 19.039466 29.790700 m 26.353334 29.790700 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 19.427663 29.540700 m 18.927663 29.790700 l 19.427663 30.040700 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.965137 30.040700 m 26.465137 29.790700 l 25.965137 29.540700 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 22.668096 26.527090 m 22.674804 33.089010 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 22.918493 26.915031 m 22.667982 26.415287 l 22.418493 26.915542 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 22.424407 32.701069 m 22.674918 33.200813 l 22.924407 32.700558 l s 0.000000 0.000000 0.000000 srgb gsave 20.738000 29.259800 translate 0.035278 -0.035278 scale start_ol 4051 3625 moveto 4051 3767 3824 3984 conicto 3597 4201 3597 4430 conicto 3597 4604 3705 4702 conicto 3813 4800 3997 4800 conicto 4245 4800 4423 4609 conicto 4602 4419 4602 4159 conicto 4602 3854 4413 3381 conicto 4224 2908 3943 2505 conicto 3111 1331 2441 569 conicto 1772 -192 1566 -192 conicto 1469 -192 1469 189 conicto 1469 656 1393 1651 conicto 1318 2647 1231 3212 conicto 1123 3962 993 4179 conicto 864 4397 551 4397 conicto 346 4397 227 4386 conicto 227 4528 lineto 605 4593 886 4647 conicto 1167 4702 1275 4734 conicto 1383 4767 1469 4783 conicto 1555 4800 1642 4800 conicto 1815 4800 1993 3516 conicto 2171 2233 2236 765 conicto 2571 1113 lineto 3143 1722 3597 2488 conicto 4051 3255 4051 3625 conicto end_ol grestore gsave 21.329939 29.259800 translate 0.035278 -0.035278 scale start_ol 961 4414 moveto 605 4414 lineto 583 4570 lineto 2247 4800 2268 4800 conicto 2322 4800 2322 4758 conicto 1977 3589 lineto 2452 4243 2873 4521 conicto 3295 4800 3824 4800 conicto 4396 4800 4731 4434 conicto 5066 4069 5066 3437 conicto 5066 2140 4034 1006 conicto 3003 -128 1826 -128 conicto 1469 -128 1113 77 conicto 713 -1429 713 -1747 conicto 713 -2077 1404 -2077 conicto 1404 -2240 lineto -810 -2240 lineto -810 -2066 lineto -670 -2066 -583 -2049 conicto -497 -2033 -410 -1983 conicto -324 -1934 -281 -1874 conicto -238 -1815 -173 -1678 conicto -108 -1542 -70 -1405 conicto -32 -1269 32 -1006 conicto 97 -744 156 -487 conicto 216 -231 324 190 conicto 432 611 540 1026 conicto 1307 3955 1307 4119 conicto 1307 4217 1188 4315 conicto 1069 4414 961 4414 conicto 4094 3415 moveto 4094 4352 3381 4352 conicto 2981 4352 2576 3997 conicto 2171 3643 1966 3109 conicto 1728 2498 1496 1637 conicto 1264 777 1264 505 conicto 1264 330 1409 215 conicto 1555 101 1782 101 conicto 2430 101 2986 690 conicto 3543 1279 3818 2030 conicto 4094 2782 4094 3415 conicto end_ol grestore gsave 22.044264 29.259800 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore gsave 22.348974 29.259800 translate 0.035278 -0.035278 scale start_ol end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 22.667600 26.041400 0.212500 0.212500 0 360 ellipse f n 22.667600 26.041400 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 22.667600 26.041400 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 0.000000 1.000000 srgb n 22.675300 33.574700 0.212500 0.212500 0 360 ellipse f n 22.675300 33.574700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 22.675300 33.574700 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 1.000000 0.647059 0.000000 srgb n 26.837800 29.790700 0.212500 0.212500 0 360 ellipse f n 26.837800 29.790700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 26.837800 29.790700 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 1.000000 0.000000 srgb n 18.555000 29.790700 0.212500 0.212500 0 360 ellipse f n 18.555000 29.790700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 18.555000 29.790700 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.882353 0.894118 srgb n 9.800000 27.800000 m 21.163201 27.752054 l s [] 0 sd 0 slj 0 slc n 21.538198 27.750472 m 21.039257 28.002579 l 21.163201 27.752054 l 21.037147 27.502584 l ef n 21.538198 27.750472 m 21.039257 28.002579 l 21.163201 27.752054 l 21.037147 27.502584 l cp s gsave 15.550000 27.300000 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 1934 -128 1649 -32 conicto 1364 63 1183 230 conicto 1002 398 917 628 conicto 832 859 832 1130 conicto 832 4416 lineto 182 4416 lineto 182 4776 lineto 948 4992 lineto 1570 6144 lineto 2368 6144 lineto 2368 4992 lineto 3414 4992 lineto 3414 4416 lineto 2368 4416 lineto 2368 1211 lineto 2368 864 2512 688 conicto 2656 512 2891 512 conicto 3072 512 3250 538 conicto 3429 565 3584 597 conicto 3584 163 lineto 3509 110 3365 57 conicto 3222 4 3049 -35 conicto 2876 -75 2687 -101 conicto 2498 -128 2333 -128 conicto end_ol grestore showpage opengv/doc/addons/images/relative_noncentral.eps0000664016516101651610000014756113344612246021056 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/relative_noncentral.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 12:06:15 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 1004 649 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -24.047130 -32.969300 translate %%EndProlog 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 25.342713 15.402668 m 29.003536 26.286368 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 29.443800 17.818700 m 32.365126 30.929505 l s 0.000000 0.862745 0.945098 srgb gsave 40.828800 18.200300 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 1934 -128 1649 -32 conicto 1364 63 1183 230 conicto 1002 398 917 628 conicto 832 859 832 1130 conicto 832 4416 lineto 182 4416 lineto 182 4776 lineto 948 4992 lineto 1570 6144 lineto 2368 6144 lineto 2368 4992 lineto 3414 4992 lineto 3414 4416 lineto 2368 4416 lineto 2368 1211 lineto 2368 864 2512 688 conicto 2656 512 2891 512 conicto 3072 512 3250 538 conicto 3429 565 3584 597 conicto 3584 163 lineto 3509 110 3365 57 conicto 3222 4 3049 -35 conicto 2876 -75 2687 -101 conicto 2498 -128 2333 -128 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.678431 0.678431 0.678431 srgb n 38.865500 21.222300 0.212500 0.212500 0 360 ellipse f n 38.865500 21.222300 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 38.865500 21.222300 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 29.087300 26.535400 0.212500 0.212500 0 360 ellipse f n 29.087300 26.535400 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 29.087300 26.535400 0.212500 0.212500 0 360 ellipse cp s gsave 29.605400 27.674000 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 37.931300 22.256200 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 30.467900 27.969000 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 38.714200 22.611100 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 1.000000 srgb n 35.579088 52.310620 38.672401 38.672401 267.629700 299.986848 ellipse s 0.100000 slw [] 0 sd 0 slj 0 slc n 34.355640 13.402641 m 33.867979 13.675930 l 34.379207 13.902085 l s gsave 45.146100 14.063900 translate 0.035278 -0.035278 scale start_ol 2752 3008 moveto 2752 512 lineto 3660 374 lineto 3660 0 lineto 249 0 lineto 249 374 lineto 1088 512 lineto 1088 6592 lineto 180 6726 lineto 180 7104 lineto 3559 7104 lineto 4444 7104 5039 6958 conicto 5634 6813 5992 6550 conicto 6350 6288 6503 5922 conicto 6656 5557 6656 5117 conicto 6656 4783 6582 4481 conicto 6508 4179 6342 3924 conicto 6176 3670 5905 3474 conicto 5634 3278 5233 3156 conicto 7113 512 lineto 7872 374 lineto 7872 0 lineto 5580 0 lineto 3599 3008 lineto 2752 3008 lineto 4992 5107 moveto 4992 5532 4908 5806 conicto 4825 6081 4642 6240 conicto 4459 6400 4172 6464 conicto 3885 6528 3483 6528 conicto 2752 6528 lineto 2752 3584 lineto 3509 3584 lineto 3922 3584 4206 3669 conicto 4491 3754 4666 3938 conicto 4841 4122 4916 4409 conicto 4992 4697 4992 5107 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 25.340795 15.399849 m 26.646384 19.248647 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 26.284930 18.961336 m 26.682300 19.354525 l 26.758429 18.800716 l s gsave 25.124796 18.886598 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 25.674796 19.161598 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 31.250000 14.000000 m 28.917663 13.451215 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.352800 13.296773 m 28.808831 13.425607 l 29.238280 13.783481 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.150000 14.000000 m 31.240493 16.126595 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 30.974215 15.749378 m 31.245247 16.238298 l 31.473763 15.728121 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.135200 13.971900 m 32.563144 12.126834 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 32.523258 12.586840 m 32.631572 12.038417 l 32.127845 12.280820 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.862745 0.945098 srgb n 31.104400 13.925000 m 55.832155 19.649568 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 55.397576 19.805573 m 55.941077 19.674784 l 55.510345 19.318456 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 31.150000 14.000000 m 29.492529 17.646436 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.425574 17.189584 m 29.446265 17.748218 l 29.880758 17.396485 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 31.150000 14.000000 m 34.811493 18.733335 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 34.376231 18.579248 m 34.879901 18.821768 l 34.771715 18.273320 l s gsave 26.586348 14.180599 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 27.286348 14.505599 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 28.838272 15.951046 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 29.488272 16.276046 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.000000 0.862745 0.945098 srgb gsave 41.856600 18.200000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 42.213763 18.200000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 42.570925 18.200000 translate 0.035278 -0.035278 scale start_ol 5568 2752 moveto 5568 2240 lineto 512 2240 lineto 512 2752 lineto 5568 2752 lineto 5568 4928 moveto 5568 4416 lineto 512 4416 lineto 512 4928 lineto 5568 4928 lineto end_ol grestore gsave 43.377665 18.200000 translate 0.035278 -0.035278 scale start_ol 2432 1856 moveto 1984 1856 lineto 1847 3648 lineto 2626 3800 lineto 2822 3836 2985 3927 conicto 3149 4019 3269 4194 conicto 3389 4369 3454 4643 conicto 3520 4918 3520 5320 conicto 3520 5701 3451 5967 conicto 3382 6234 3228 6401 conicto 3074 6568 2821 6644 conicto 2568 6720 2199 6720 conicto 1869 6720 1596 6648 conicto 1324 6577 1132 6470 conicto 939 5632 lineto 576 5632 lineto 576 6946 lineto 956 7044 1339 7106 conicto 1722 7168 2178 7168 conicto 3329 7168 3904 6718 conicto 4480 6268 4480 5389 conicto 4480 5022 4392 4690 conicto 4304 4358 4104 4088 conicto 3905 3819 3585 3622 conicto 3266 3426 2803 3332 conicto 2500 3264 lineto 2432 1856 lineto 2880 512 moveto 2880 380 2829 263 conicto 2779 147 2694 59 conicto 2609 -28 2492 -78 conicto 2375 -128 2243 -128 conicto 2105 -128 1988 -78 conicto 1871 -28 1786 59 conicto 1701 147 1650 263 conicto 1600 380 1600 512 conicto 1600 644 1650 763 conicto 1701 882 1786 967 conicto 1871 1052 1988 1102 conicto 2105 1152 2243 1152 conicto 2375 1152 2492 1102 conicto 2609 1052 2694 967 conicto 2779 882 2829 763 conicto 2880 644 2880 512 conicto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 46.649200 14.070000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 47.006363 14.070000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 47.363525 14.070000 translate 0.035278 -0.035278 scale start_ol 5568 2752 moveto 5568 2240 lineto 512 2240 lineto 512 2752 lineto 5568 2752 lineto 5568 4928 moveto 5568 4416 lineto 512 4416 lineto 512 4928 lineto 5568 4928 lineto end_ol grestore gsave 48.170265 14.070000 translate 0.035278 -0.035278 scale start_ol 2432 1856 moveto 1984 1856 lineto 1847 3648 lineto 2626 3800 lineto 2822 3836 2985 3927 conicto 3149 4019 3269 4194 conicto 3389 4369 3454 4643 conicto 3520 4918 3520 5320 conicto 3520 5701 3451 5967 conicto 3382 6234 3228 6401 conicto 3074 6568 2821 6644 conicto 2568 6720 2199 6720 conicto 1869 6720 1596 6648 conicto 1324 6577 1132 6470 conicto 939 5632 lineto 576 5632 lineto 576 6946 lineto 956 7044 1339 7106 conicto 1722 7168 2178 7168 conicto 3329 7168 3904 6718 conicto 4480 6268 4480 5389 conicto 4480 5022 4392 4690 conicto 4304 4358 4104 4088 conicto 3905 3819 3585 3622 conicto 3266 3426 2803 3332 conicto 2500 3264 lineto 2432 1856 lineto 2880 512 moveto 2880 380 2829 263 conicto 2779 147 2694 59 conicto 2609 -28 2492 -78 conicto 2375 -128 2243 -128 conicto 2105 -128 1988 -78 conicto 1871 -28 1786 59 conicto 1701 147 1650 263 conicto 1600 380 1600 512 conicto 1600 644 1650 763 conicto 1701 882 1786 967 conicto 1871 1052 1988 1102 conicto 2105 1152 2243 1152 conicto 2375 1152 2492 1102 conicto 2609 1052 2694 967 conicto 2779 882 2829 763 conicto 2880 644 2880 512 conicto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 30.188700 13.207800 translate 0.035278 -0.035278 scale start_ol 4051 3625 moveto 4051 3767 3824 3984 conicto 3597 4201 3597 4430 conicto 3597 4604 3705 4702 conicto 3813 4800 3997 4800 conicto 4245 4800 4423 4609 conicto 4602 4419 4602 4159 conicto 4602 3854 4413 3381 conicto 4224 2908 3943 2505 conicto 3111 1331 2441 569 conicto 1772 -192 1566 -192 conicto 1469 -192 1469 189 conicto 1469 656 1393 1651 conicto 1318 2647 1231 3212 conicto 1123 3962 993 4179 conicto 864 4397 551 4397 conicto 346 4397 227 4386 conicto 227 4528 lineto 605 4593 886 4647 conicto 1167 4702 1275 4734 conicto 1383 4767 1469 4783 conicto 1555 4800 1642 4800 conicto 1815 4800 1993 3516 conicto 2171 2233 2236 765 conicto 2571 1113 lineto 3143 1722 3597 2488 conicto 4051 3255 4051 3625 conicto end_ol grestore gsave 30.780639 13.207800 translate 0.035278 -0.035278 scale start_ol 961 4414 moveto 605 4414 lineto 583 4570 lineto 2247 4800 2268 4800 conicto 2322 4800 2322 4758 conicto 1977 3589 lineto 2452 4243 2873 4521 conicto 3295 4800 3824 4800 conicto 4396 4800 4731 4434 conicto 5066 4069 5066 3437 conicto 5066 2140 4034 1006 conicto 3003 -128 1826 -128 conicto 1469 -128 1113 77 conicto 713 -1429 713 -1747 conicto 713 -2077 1404 -2077 conicto 1404 -2240 lineto -810 -2240 lineto -810 -2066 lineto -670 -2066 -583 -2049 conicto -497 -2033 -410 -1983 conicto -324 -1934 -281 -1874 conicto -238 -1815 -173 -1678 conicto -108 -1542 -70 -1405 conicto -32 -1269 32 -1006 conicto 97 -744 156 -487 conicto 216 -231 324 190 conicto 432 611 540 1026 conicto 1307 3955 1307 4119 conicto 1307 4217 1188 4315 conicto 1069 4414 961 4414 conicto 4094 3415 moveto 4094 4352 3381 4352 conicto 2981 4352 2576 3997 conicto 2171 3643 1966 3109 conicto 1728 2498 1496 1637 conicto 1264 777 1264 505 conicto 1264 330 1409 215 conicto 1555 101 1782 101 conicto 2430 101 2986 690 conicto 3543 1279 3818 2030 conicto 4094 2782 4094 3415 conicto end_ol grestore 0.000000 0.862745 0.945098 srgb gsave 41.450000 18.550000 translate 0.035278 -0.035278 scale start_ol 2452 2172 moveto 2452 2257 2314 2388 conicto 2177 2520 2177 2657 conicto 2177 2762 2242 2821 conicto 2308 2880 2419 2880 conicto 2570 2880 2678 2765 conicto 2786 2650 2786 2493 conicto 2786 2310 2671 2024 conicto 2557 1739 2387 1497 conicto 1883 790 1477 331 conicto 1072 -128 948 -128 conicto 889 -128 889 102 conicto 889 384 843 983 conicto 798 1583 745 1923 conicto 680 2375 601 2506 conicto 523 2637 333 2637 conicto 209 2637 137 2630 conicto 137 2716 lineto 366 2756 536 2788 conicto 706 2821 771 2840 conicto 837 2860 889 2870 conicto 942 2880 994 2880 conicto 1099 2880 1206 2107 conicto 1314 1334 1354 449 conicto 1556 659 lineto 1903 1026 2177 1487 conicto 2452 1949 2452 2172 conicto end_ol grestore gsave 41.809660 18.550000 translate 0.035278 -0.035278 scale start_ol 582 2660 moveto 366 2660 lineto 353 2749 lineto 1360 2880 1373 2880 conicto 1406 2880 1406 2856 conicto 1197 2164 lineto 1484 2550 1739 2715 conicto 1994 2880 2315 2880 conicto 2661 2880 2864 2661 conicto 3067 2443 3067 2065 conicto 3067 1290 2442 613 conicto 1818 -64 1105 -64 conicto 889 -64 674 47 conicto 432 -829 432 -1015 conicto 432 -1207 850 -1207 conicto 850 -1344 lineto -490 -1344 lineto -490 -1207 lineto -405 -1207 -353 -1197 conicto -301 -1188 -248 -1158 conicto -196 -1129 -170 -1093 conicto -144 -1057 -104 -975 conicto -65 -894 -42 -812 conicto -20 -731 19 -574 conicto 59 -418 95 -264 conicto 131 -111 196 140 conicto 262 391 327 639 conicto 791 2386 791 2484 conicto 791 2543 719 2601 conicto 647 2660 582 2660 conicto 2478 2058 moveto 2478 2624 2047 2624 conicto 1805 2624 1559 2410 conicto 1314 2196 1190 1875 conicto 1046 1507 905 987 conicto 765 468 765 304 conicto 765 198 853 129 conicto 942 60 1079 60 conicto 1471 60 1808 415 conicto 2145 770 2311 1224 conicto 2478 1678 2478 2058 conicto end_ol grestore gsave 42.241749 18.550000 translate 0.035278 -0.035278 scale start_ol 863 2752 moveto 948 3797 1000 3999 conicto 1138 4326 1367 4352 conicto 1452 4352 1514 4296 conicto 1576 4241 1576 4163 conicto 1576 3999 1000 2752 conicto 863 2752 lineto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 46.300000 14.300000 translate 0.035278 -0.035278 scale start_ol 2452 2172 moveto 2452 2257 2314 2388 conicto 2177 2520 2177 2657 conicto 2177 2762 2242 2821 conicto 2308 2880 2419 2880 conicto 2570 2880 2678 2765 conicto 2786 2650 2786 2493 conicto 2786 2310 2671 2024 conicto 2557 1739 2387 1497 conicto 1883 790 1477 331 conicto 1072 -128 948 -128 conicto 889 -128 889 102 conicto 889 384 843 983 conicto 798 1583 745 1923 conicto 680 2375 601 2506 conicto 523 2637 333 2637 conicto 209 2637 137 2630 conicto 137 2716 lineto 366 2756 536 2788 conicto 706 2821 771 2840 conicto 837 2860 889 2870 conicto 942 2880 994 2880 conicto 1099 2880 1206 2107 conicto 1314 1334 1354 449 conicto 1556 659 lineto 1903 1026 2177 1487 conicto 2452 1949 2452 2172 conicto end_ol grestore gsave 46.659660 14.300000 translate 0.035278 -0.035278 scale start_ol 582 2660 moveto 366 2660 lineto 353 2749 lineto 1360 2880 1373 2880 conicto 1406 2880 1406 2856 conicto 1197 2164 lineto 1484 2550 1739 2715 conicto 1994 2880 2315 2880 conicto 2661 2880 2864 2661 conicto 3067 2443 3067 2065 conicto 3067 1290 2442 613 conicto 1818 -64 1105 -64 conicto 889 -64 674 47 conicto 432 -829 432 -1015 conicto 432 -1207 850 -1207 conicto 850 -1344 lineto -490 -1344 lineto -490 -1207 lineto -405 -1207 -353 -1197 conicto -301 -1188 -248 -1158 conicto -196 -1129 -170 -1093 conicto -144 -1057 -104 -975 conicto -65 -894 -42 -812 conicto -20 -731 19 -574 conicto 59 -418 95 -264 conicto 131 -111 196 140 conicto 262 391 327 639 conicto 791 2386 791 2484 conicto 791 2543 719 2601 conicto 647 2660 582 2660 conicto 2478 2058 moveto 2478 2624 2047 2624 conicto 1805 2624 1559 2410 conicto 1314 2196 1190 1875 conicto 1046 1507 905 987 conicto 765 468 765 304 conicto 765 198 853 129 conicto 942 60 1079 60 conicto 1471 60 1808 415 conicto 2145 770 2311 1224 conicto 2478 1678 2478 2058 conicto end_ol grestore gsave 47.091749 14.300000 translate 0.035278 -0.035278 scale start_ol 863 2752 moveto 948 3797 1000 3999 conicto 1138 4326 1367 4352 conicto 1452 4352 1514 4296 conicto 1576 4241 1576 4163 conicto 1576 3999 1000 2752 conicto 863 2752 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 56.034200 19.686500 m 54.332560 21.266549 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 54.446921 20.819203 m 54.250630 21.342624 l 54.787142 21.185605 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 55.999000 19.743700 m 56.684313 17.513741 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 56.809245 17.958250 m 56.717156 17.406870 l 56.331306 17.811369 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 56.011500 19.712500 m 53.220014 23.115993 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 53.272894 22.657299 m 53.149112 23.202440 l 53.659494 22.974381 l s gsave 52.758301 20.116925 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 53.472626 20.116925 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 57.818473 23.407026 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 58.532799 23.407026 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 58.468473 23.732026 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 56.600000 19.500000 translate 0.035278 -0.035278 scale start_ol 4051 3625 moveto 4051 3767 3824 3984 conicto 3597 4201 3597 4430 conicto 3597 4604 3705 4702 conicto 3813 4800 3997 4800 conicto 4245 4800 4423 4609 conicto 4602 4419 4602 4159 conicto 4602 3854 4413 3381 conicto 4224 2908 3943 2505 conicto 3111 1331 2441 569 conicto 1772 -192 1566 -192 conicto 1469 -192 1469 189 conicto 1469 656 1393 1651 conicto 1318 2647 1231 3212 conicto 1123 3962 993 4179 conicto 864 4397 551 4397 conicto 346 4397 227 4386 conicto 227 4528 lineto 605 4593 886 4647 conicto 1167 4702 1275 4734 conicto 1383 4767 1469 4783 conicto 1555 4800 1642 4800 conicto 1815 4800 1993 3516 conicto 2171 2233 2236 765 conicto 2571 1113 lineto 3143 1722 3597 2488 conicto 4051 3255 4051 3625 conicto end_ol grestore gsave 57.191939 19.500000 translate 0.035278 -0.035278 scale start_ol 961 4414 moveto 605 4414 lineto 583 4570 lineto 2247 4800 2268 4800 conicto 2322 4800 2322 4758 conicto 1977 3589 lineto 2452 4243 2873 4521 conicto 3295 4800 3824 4800 conicto 4396 4800 4731 4434 conicto 5066 4069 5066 3437 conicto 5066 2140 4034 1006 conicto 3003 -128 1826 -128 conicto 1469 -128 1113 77 conicto 713 -1429 713 -1747 conicto 713 -2077 1404 -2077 conicto 1404 -2240 lineto -810 -2240 lineto -810 -2066 lineto -670 -2066 -583 -2049 conicto -497 -2033 -410 -1983 conicto -324 -1934 -281 -1874 conicto -238 -1815 -173 -1678 conicto -108 -1542 -70 -1405 conicto -32 -1269 32 -1006 conicto 97 -744 156 -487 conicto 216 -231 324 190 conicto 432 611 540 1026 conicto 1307 3955 1307 4119 conicto 1307 4217 1188 4315 conicto 1069 4414 961 4414 conicto 4094 3415 moveto 4094 4352 3381 4352 conicto 2981 4352 2576 3997 conicto 2171 3643 1966 3109 conicto 1728 2498 1496 1637 conicto 1264 777 1264 505 conicto 1264 330 1409 215 conicto 1555 101 1782 101 conicto 2430 101 2986 690 conicto 3543 1279 3818 2030 conicto 4094 2782 4094 3415 conicto end_ol grestore gsave 57.906264 19.500000 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.898039 0.898039 0.898039 srgb n 36.993600 27.562000 0.212500 0.212500 0 360 ellipse f n 36.993600 27.562000 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 36.993600 27.562000 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.678431 0.678431 0.678431 srgb n 32.422300 31.186100 0.212500 0.212500 0 360 ellipse f n 32.422300 31.186100 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 32.422300 31.186100 0.212500 0.212500 0 360 ellipse cp s gsave 31.124800 32.486800 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 31.987300 32.781800 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 31.111900 14.016200 m 25.514372 15.350808 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.834002 15.017591 m 25.405617 15.376738 l 25.949966 15.503958 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.144300 14.019300 m 35.830070 11.430153 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 35.611202 11.836716 m 35.927928 11.376081 l 35.369384 11.399081 l s gsave 33.103550 11.499716 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 33.703550 11.824716 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.678431 0.678431 0.678431 srgb n 34.902459 18.910201 m 36.932081 27.307473 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 35.934086 11.344934 m 38.790891 20.970905 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 55.986500 19.718700 m 55.703520 14.388008 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 55.973747 14.762406 m 55.697593 14.276362 l 55.474450 14.788911 l s gsave 56.225000 16.600000 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 56.939325 16.600000 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 56.825000 16.925000 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.000000 0.862745 0.945098 srgb gsave 41.425000 17.580000 translate 0.035278 -0.035278 scale start_ol 2452 2172 moveto 2452 2257 2314 2388 conicto 2177 2520 2177 2657 conicto 2177 2762 2242 2821 conicto 2308 2880 2419 2880 conicto 2570 2880 2678 2765 conicto 2786 2650 2786 2493 conicto 2786 2310 2671 2024 conicto 2557 1739 2387 1497 conicto 1883 790 1477 331 conicto 1072 -128 948 -128 conicto 889 -128 889 102 conicto 889 384 843 983 conicto 798 1583 745 1923 conicto 680 2375 601 2506 conicto 523 2637 333 2637 conicto 209 2637 137 2630 conicto 137 2716 lineto 366 2756 536 2788 conicto 706 2821 771 2840 conicto 837 2860 889 2870 conicto 942 2880 994 2880 conicto 1099 2880 1206 2107 conicto 1314 1334 1354 449 conicto 1556 659 lineto 1903 1026 2177 1487 conicto 2452 1949 2452 2172 conicto end_ol grestore gsave 41.784660 17.580000 translate 0.035278 -0.035278 scale start_ol 582 2660 moveto 366 2660 lineto 353 2749 lineto 1360 2880 1373 2880 conicto 1406 2880 1406 2856 conicto 1197 2164 lineto 1484 2550 1739 2715 conicto 1994 2880 2315 2880 conicto 2661 2880 2864 2661 conicto 3067 2443 3067 2065 conicto 3067 1290 2442 613 conicto 1818 -64 1105 -64 conicto 889 -64 674 47 conicto 432 -829 432 -1015 conicto 432 -1207 850 -1207 conicto 850 -1344 lineto -490 -1344 lineto -490 -1207 lineto -405 -1207 -353 -1197 conicto -301 -1188 -248 -1158 conicto -196 -1129 -170 -1093 conicto -144 -1057 -104 -975 conicto -65 -894 -42 -812 conicto -20 -731 19 -574 conicto 59 -418 95 -264 conicto 131 -111 196 140 conicto 262 391 327 639 conicto 791 2386 791 2484 conicto 791 2543 719 2601 conicto 647 2660 582 2660 conicto 2478 2058 moveto 2478 2624 2047 2624 conicto 1805 2624 1559 2410 conicto 1314 2196 1190 1875 conicto 1046 1507 905 987 conicto 765 468 765 304 conicto 765 198 853 129 conicto 942 60 1079 60 conicto 1471 60 1808 415 conicto 2145 770 2311 1224 conicto 2478 1678 2478 2058 conicto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 46.275000 13.430000 translate 0.035278 -0.035278 scale start_ol 2452 2172 moveto 2452 2257 2314 2388 conicto 2177 2520 2177 2657 conicto 2177 2762 2242 2821 conicto 2308 2880 2419 2880 conicto 2570 2880 2678 2765 conicto 2786 2650 2786 2493 conicto 2786 2310 2671 2024 conicto 2557 1739 2387 1497 conicto 1883 790 1477 331 conicto 1072 -128 948 -128 conicto 889 -128 889 102 conicto 889 384 843 983 conicto 798 1583 745 1923 conicto 680 2375 601 2506 conicto 523 2637 333 2637 conicto 209 2637 137 2630 conicto 137 2716 lineto 366 2756 536 2788 conicto 706 2821 771 2840 conicto 837 2860 889 2870 conicto 942 2880 994 2880 conicto 1099 2880 1206 2107 conicto 1314 1334 1354 449 conicto 1556 659 lineto 1903 1026 2177 1487 conicto 2452 1949 2452 2172 conicto end_ol grestore gsave 46.634660 13.430000 translate 0.035278 -0.035278 scale start_ol 582 2660 moveto 366 2660 lineto 353 2749 lineto 1360 2880 1373 2880 conicto 1406 2880 1406 2856 conicto 1197 2164 lineto 1484 2550 1739 2715 conicto 1994 2880 2315 2880 conicto 2661 2880 2864 2661 conicto 3067 2443 3067 2065 conicto 3067 1290 2442 613 conicto 1818 -64 1105 -64 conicto 889 -64 674 47 conicto 432 -829 432 -1015 conicto 432 -1207 850 -1207 conicto 850 -1344 lineto -490 -1344 lineto -490 -1207 lineto -405 -1207 -353 -1197 conicto -301 -1188 -248 -1158 conicto -196 -1129 -170 -1093 conicto -144 -1057 -104 -975 conicto -65 -894 -42 -812 conicto -20 -731 19 -574 conicto 59 -418 95 -264 conicto 131 -111 196 140 conicto 262 391 327 639 conicto 791 2386 791 2484 conicto 791 2543 719 2601 conicto 647 2660 582 2660 conicto 2478 2058 moveto 2478 2624 2047 2624 conicto 1805 2624 1559 2410 conicto 1314 2196 1190 1875 conicto 1046 1507 905 987 conicto 765 468 765 304 conicto 765 198 853 129 conicto 942 60 1079 60 conicto 1471 60 1808 415 conicto 2145 770 2311 1224 conicto 2478 1678 2478 2058 conicto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 55.668741 14.210566 m 39.108052 21.121087 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.678431 0.678431 0.678431 srgb n 53.124060 23.243036 m 37.246623 27.494253 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 58.350972 25.925267 m 32.679466 31.133922 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 51.450532 21.340256 m 29.341179 26.476422 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 29.437500 17.806300 m 30.181502 21.063209 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.851329 20.740436 m 30.206401 21.172204 l 30.338772 20.629086 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 34.875280 18.810177 m 35.652844 22.062705 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 35.319435 21.743276 m 35.678840 22.171444 l 35.805732 21.627019 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 35.934086 11.367860 m 36.925020 14.706876 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 36.574906 14.405850 m 36.956829 14.814059 l 37.054243 14.263595 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 51.487898 21.341800 m 48.092534 22.094253 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 48.417445 21.766184 m 47.983379 22.118443 l 48.525626 22.254340 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 58.340900 25.915706 m 55.108181 26.590268 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 55.437126 26.266243 m 54.998735 26.613105 l 55.539260 26.755701 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 53.124060 23.243036 m 50.084326 24.077892 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 50.392450 23.734009 m 49.976514 24.107503 l 50.524871 24.216155 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 55.996700 19.711500 m 58.654470 20.744026 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 58.202089 20.836482 m 58.758685 20.784513 l 58.383152 20.370418 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 55.665500 14.237346 m 52.413961 15.570042 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 52.678345 15.191495 m 52.310510 15.612443 l 52.867969 15.654143 l s gsave 30.865951 20.976277 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 31.415951 21.251277 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 37.191399 12.845615 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 37.741399 13.120615 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore gsave 48.286347 21.265975 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 48.763399 21.265975 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 48.836347 21.540975 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 55.554824 27.927031 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 56.031876 27.927031 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 56.104824 28.202031 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 52.647297 14.359518 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 53.124349 14.359518 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 53.197297 14.634518 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.627451 0.125490 0.941176 srgb gsave 53.389525 20.373149 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc n 55.996700 19.711500 m 58.250254 25.784403 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 57.880816 25.507433 m 58.289150 25.889223 l 58.349582 25.333482 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 56.046700 19.761500 m 51.638547 21.311916 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 51.921805 20.947277 m 51.533077 21.349011 l 52.087701 21.418953 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 25.356765 15.444568 m 24.346130 14.930863 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 24.805468 14.883902 m 24.246464 14.880203 l 24.578907 15.329626 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 25.364421 15.435724 m 24.530299 16.297595 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 24.620623 15.844784 m 24.452546 16.377935 l 24.979913 16.192506 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 25.368982 15.427298 m 25.993085 16.338832 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.567494 16.159756 m 26.056248 16.431084 l 25.980058 15.877284 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 29.425614 17.789012 m 30.631252 17.982003 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 30.208420 18.167501 m 30.741650 17.999674 l 30.287451 17.673786 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 29.423024 17.789184 m 29.376193 19.018026 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.141158 18.620590 m 29.371935 19.129748 l 29.640795 18.639631 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 29.422372 17.781015 m 28.491310 18.319815 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 28.702084 17.908998 m 28.394542 18.375814 l 28.952520 18.341758 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 34.866731 18.819176 m 33.935669 19.357977 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 34.146444 18.947160 m 33.838901 19.413976 l 34.396880 19.379920 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 34.893720 18.810502 m 35.683537 19.665210 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 35.236468 19.549774 m 35.759415 19.747323 l 35.603686 19.210435 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 34.882153 18.821104 m 35.161029 17.770803 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 35.303034 18.210156 m 35.189720 17.662744 l 34.819779 18.081843 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 35.943765 11.398744 m 35.927251 10.442648 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 36.183918 10.826469 m 35.925320 10.330861 l 35.683992 10.835104 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 35.934126 11.398744 m 34.890516 11.254944 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 35.309204 11.060273 m 34.779759 11.239682 l 35.240954 11.555593 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 35.936929 11.401829 m 35.713300 12.346616 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 35.559437 11.911274 m 35.687548 12.455413 l 36.045992 12.026441 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 55.693352 14.207675 m 54.649742 14.063875 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 55.068430 13.869204 m 54.538985 14.048614 l 55.000180 14.364524 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 55.691424 14.218278 m 55.925041 13.282377 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 56.073583 13.719563 m 55.952118 13.173902 l 55.588468 13.598470 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 55.700366 14.202413 m 55.588425 15.252772 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 55.380971 14.840268 m 55.576577 15.363946 l 55.878156 14.893255 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 51.505572 21.348117 m 51.385669 20.210850 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 51.674993 20.570694 m 51.373946 20.099662 l 51.177749 20.623119 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 51.524447 21.354241 m 52.319378 21.938085 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 51.858514 21.909784 m 52.409488 22.004268 l 52.154490 21.506798 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 51.508095 21.322807 m 50.678768 21.988332 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 50.825062 21.550388 m 50.591571 22.058308 l 51.138001 21.940349 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 53.106652 23.230885 m 52.918097 24.202797 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 52.746607 23.774092 m 52.896804 24.312554 l 53.237455 23.869319 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 53.083851 23.219203 m 54.309789 23.234036 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 53.918596 23.479321 m 54.421585 23.235389 l 53.924646 22.979358 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 53.078405 23.220341 m 52.626315 22.290812 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 53.020923 22.530565 m 52.577415 22.190270 l 52.571284 22.749253 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 58.253092 25.923313 m 59.198884 26.725547 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 58.741126 26.665092 m 59.284146 26.797868 l 59.064555 26.283786 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 58.242981 25.916754 m 57.485526 26.676483 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 57.582569 26.225064 m 57.406587 26.755658 l 57.936652 26.578087 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 58.259162 25.912853 m 58.795436 25.011743 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 58.811741 25.473188 m 58.852614 24.915667 l 58.382074 25.217481 l s showpage opengv/doc/addons/images/central.dia0000664016516101651610000000247413344612246016407 0ustar dimadima‹íZ]o£8}ï¯@ékÆÁc{:íH»ÒhFÚ‡™}ŽœàïˆÀI›}Øß¾—6 ¶ù€mf@ ÖåÛø__ûÓçÇyh­T’ê8º`d,Mc_GÁíà¯ï_>ðÁ绫O¾–á$rnÁQš=ÝfÆ,>ŽF(\§ÒÄ õ¥jô¯ C9£Ñàîʲ¶øÒȬ¬,•Æ$z²4ÊŠä\Ý&rú#Hâeä «Òn‡qb­dx;¸¾Ï¯Á¨t3Úñó‚ï… Ô$QòG³k.!Žq½PIÕí|§LÌz±gÒà'»oÙ”V)EÁÝõWeŒJ®‹j•…u•m2s™:ÚÇ‚þ ‹Î ˆ:"»<Ì©cæ<õËáp“náÂná’nát:^ĉI¤6û“8•Œ T“,Õñ8éT†0Ä^j>Þû½6&~¥þ÷2LßÒ€¢ø™q‡²7H´ÿ2yw,¼‰¦è©¹4Ÿ‚Pä8ž-øl¡ÄN½6ùâ Ï\»ø†ØSJ† aAì.³ßÈ};¨•í:nfJ„CzÚü¬´!ç¢ m—3ŽÃIsƒ]dÃ*bˆ bðß_^ž_2#¨×O/?-Oœsð„ÐÖ™‚AÛ±7ÄÈ%˜‘,cœc€ر½Ø²×Æ3Œ§.T’¶É7½ÒÀ‚_wW@µ¸,QÖÓòÐÒ=-=R:-~ÂsóÕ cì{ˆÀ#Ì]Ä}µÍ¬1õöx>¡Âzröä<–œôätóÙ« r¢('§pÅ @VƆÁ´éteÖ¶³ÆT *ˆr$„༧gOÏWéù]=š-zâ’žÞÉôvÀ˜%­´EŽÈR‹@J—晓cSš&ëŠWò雦í¡|rÇ®²_ùذUùB~¿i³(ŽLRVnÝ˹×P!¥+5ë, \¼ú‡ WÊè©Ü•Ãk0S:˜ÕÖakaJ8„6‚dÉ­Ó0wßà1@UÑjÜß®c€d¨ƒh®ê?æFÄÞŠR»¡qVy•šõÔéD‰ØÉJdà ÈSü6m{·#–Ö6â"¹-Z÷ZÔ¶5 Á^.PøÉ‚D?%%ü61ÊA0b¢Øw%œf˜ü"¢£zEj[‘jÆ`¯F¨Fâ<A`Õò&€¸pËÅ(¤6¹)úÅ”âV{÷r[—¢šØKÑ{–¢¦S6ç9”†yžë„±EAbÈ%Ô+އqî'Ó\š¥NÞÉ^hm;÷M¢q0TŒ1Ï¡¿TN7GÈŰyh»}ºø¤‹ñ9NØåß°KZDÆE< D\äå'(»„HdÚm(ò%Qê›Jôýs<Ÿâ‘ßãe¢UÒźˆq–¯‹¸ð—uŒÔ Ã>ù_Ñâ9?`wµsÿîê?O¾©7opengv/doc/addons/images/noncentral.png0000664016516101651610000010726613344612246017156 0ustar dimadima‰PNG  IHDRS–Óî‘%bKGDÿÿÿ ½§“ IDATxœìÝw\S×ûðOa ˆ€€J¨´X nq‚[­Pµp¡ýVPkím\µn­{ €âD@p[Á‚¸ea'9¿?’:‘äfœ÷Ë?ðææÜMòäœ{ÎsX„PEQ”Ú`3EQEÉÍ|EQ”z¡™¢(ŠR/4óQEQê…f>Š¢(J½ÐÌGQE©šù(Š¢ÔÔ… X,Ö’%KjŸ9s&‹ÅJKKc$*9`Ñõ|EQjËÎÎŽÏçgffr8ñ‘²²2ssóO>ùäâÅ‹ÌÆ&;´ÏGQ¥¾|}}Ÿ>}zòäÉ×GöîÝ[\\ìããÃ`T²Fû|EQê«°°ÐÒÒrøðáGéÛ·oFFƳgÏ´´´˜MvhŸ¢(J}}þùçQQQÏŸ?šššœœìååÕ„´WQQqæÌ™ääd„)e4óQE©5???@°uëV7nШ¡Î‡®[·ÎÕÕÕØØØÅÅE___VJí¤(ŠRwÝ»w/..NIIiÓ¦M×®]ãããë?¿¢¢"...&&&&&&##ãõñ>}ú(EŸËtEQÃüüüüüüfΜYXXXO‡ïÁƒ'OžŒŽŽ¾páBYYÙû'LŸ>]–aJ íóQE©;>ŸoaaQRRbdd”]ã&_BB±cÇŽ?~÷îÝzÑÑÑÉÎÎ600q°R@ïóQE©;==½)S¦¨un‹­­m«V­X,VýŒ?^)Òhæ£(Š¢ðx<¾¾¾ï?dnn–––ðõ×_×5‡eÚ´i² Qzèh'EQ”º+..nÛ¶í'Ÿ|ד?ûì³óçÏ¿}°}ûö÷ïßÿ`¿PAÐ.EÉØÁƒÐ¿?Ì̘…ªéÖ­[)))Û·o/**úñÇ?x~yyù”)SΟ?¯««[ZZúúøŒ3”%íŽv*”‚‚‚êêj¦£ (iÓѧ'Z·F—.ðóÞ=xöŒé˜(‰]»vy{{§§§‡‡‡6¬þ“_¾|9xðàãÇ›˜˜œ;wÎØØX|œÍf‹o* :Ú©@,X`kk;sæL¦¡(©‰Ð©îßçàGaÀ ˆamÍPdT#<}útäÈ‘wîÜiÛ¶í©S§:wîŸBÈÉÉY½zµøçeË–UVV2EI™¼½ë|”ŰaˆŒÄÝ»4í)𨨨æääŒ=:66öuÚ`jjÚ³gϯ¾úJ¹ÒhæS«V­z] èÉ“';wîd6Š’¾9sðþÜ?mmÌœ‰;wpú4ÜÜÀ¦ŸHŠeÿþýnnn|>úôéÇŽÓÑÑ©qˆ#”¥bÙÛèh'ó²³³mmm+**^±²²ºwïžÒ}¢¨1±±ï14ÄÁƒ:”¡€¨úlذaΜ9B¡páÂ…¡¡¡µ.Zxö왥¥¥ück&ú ‹y+W®|;íxòä‰xÇŠR)sç¾óW¼z…#ÊP@TgΜ)‰Â–/_^×Z=eL{ }>ƽßá£Ý>J‚.]žZZ(,Dx8¾ÿ„ÀÇkׂÎjV"‘Èßßݺu\.÷¯¿þò®ç­Ò¢}>†­^½úý´àÉ“'»ví’<%C,fÍ’üܧ´´€½{¡­1f ŠŠBEEÅ„ Ö­[§­­}øða•L{ }>fåååµoßžÏç×úhûöíÓÓÓéÚ>J¥¡Mðùøáüü³ä`r2>û 99èÚ'NÀƆÉÕXqq±‡‡Ç¹sç "## ÀtD²Bû|Lúý÷ß_§=6› àí<÷ðáC:É“R5¯—7¼ý©ê舤$té‚;wЫ>´!8% yyyC‡=w¥ebb¢ §=ÐÌÇ ¼¼¼õë×àp8“'O¾xñ"ƒ„„„áÇ‹Ïùå—_h%OJÕ|û-´´àìüÎÁv휌1cŸС~ùÊÊÊ0`Àµk×:tèеkW¦#’-šù³bÅŠòòr//¯;wîìÞ½»S§NâãNNN§NJJJ5jÔÇwìØÁlœ%e}„Ä{+à¯cÇ0w.*+áíà`Ð{1rqûömGGÇôôôîÝ»ÇÇÇÛ¨Áh3Í|Ìxùò%ŸÏOKKÛ±cÇëœ÷6GGÇèèèË—/ߺu‹vû(U³paíÇ9¬^ˆp8Xº_|òrùF¦v ôüùs—‹/š©ÉNR„R yyyZµjUë£âM üñÇÇýüüüû￲¢äèäIb`@Ò·/ÉÉa:•%.ËâééYQQÁt8òCçv*Šüü|“V­Z‰Sàûìììø|~ff&‡Ã)++377ÿä“OÄ÷)J¥¤¤ÀÍ £}{?Ž.]˜HÕlÙ²Å××W øúú®[·îõ‹: {²+ ñWz65öõõýöÛoOž<9fÌñ‘½{÷ûøøÈ)DŠ’'{{$'ÃÝW®ÀÑ{÷bôh¦cR+V¬ „„„„Èä%%ؼUUÐЀžÞ;ééÕRµ U+ ,“HÞÇpŸ“úOnn.“ºN(((ÐÖÖvww}ÄÑѱeË–ååår ¢˜P^N&O&árÉÚµLG£ Ä%Z°Ùìµ²þ'½r…ØØàÃ8ræŒlƒy á¢4ŒŒŒ>ÿü󨨨çÏŸHMMMNNöòòÒÒÒb:4Š’--ìÚ…  …˜3óæA(d:&%&¦Nºzõj ;wΞ=[¶×ëÕ 7n`ìØŸ¹d‰< —Ó̧Lüüü¸˜õÆСNJõ±XÆž=ÐÒÂêÕpuEq1Ó1)¥òòòqãÆíرC__?&&fòäÉò¸ª‘ŽCDx¼:ÏñðÀ?Ê#˜ÿÐ.Š"//ÏÔÔÔÄÄD<ìY—îÝ»§¤¤´iÓ¦k×®ñ´Ú¥>.]‚‡rsññÇ8~mÛ22)**;vìÅ‹MLL¢¢¢zõê%ïÎŸÇøñ(,¬y¼m[\¿ŽV­ä íó)??¿‡Μ9³°°vø(õÒ¯’’`g‡Û·á舫W™Hi<{öÌÉÉéâÅ‹mÛ¶½xñ¢¼ÓžPˆ={0wn-iÇþ}rN{ }>Å‘››kfffjjš““SÏi|>ߢ¤¤ÄÈÈ(;;›Þä£ÔNa!<=qö,´´°u+¾ø‚é€ݽ{÷†ž™™iooòäI ù]»¼7båJde@§NÈÉÁ«WoNذ¾¾ò‹ç?´Ï§dôôô¦L™€Îm¡Ô”‘NžÄìÙ¨¨ÀäÉf: …vãÆþýûgfföë×/..N~i¯¬ ¡¡°±ÁüùÈÊB÷Ŀÿâí=G'Nd$íf>eÄãñø2ôŠ¡(æq¹X»aa`±°t)¦OGUÓ1)¢Ó§O80''gÔ¨Q±±±FFFò¸jQ‚ƒacƒÀ@俢gODFâúu¸¹Í~35×ÁÛ¶É#žZÉmýU?ñ §©©iý§ 0@>QQ”B‹Ž&-Z€89‘Ü\¦£Q,û÷ï×ÔÔ0mÚ´êêjy\² €ccɽ>}ÈéÓ5ÏiÙ’DW—¤¤È#¤:Ð>ŸÒ¸uëÖÎ;ÇWTTô£|gS”‚5 ññhÛ‰‰è×ééL¤("""&MšTYY¹`Á‚¿þú‹Ë•q¹®—/kk,]Š—/1dâ㑜ŒaÃjž)ÀŸ¢[7Ù†T?³.õ¶öù¾ûî;–––áááò Œ¢]v6éÙ“¤eKrîÓÑ0O\ŒÅb…„„ÈübÙÙÄߟèéIúy®®$>¾¾óõõ‰Ì£úšùÅ‹/˜™™1E)!>Ÿxx€ðxdëV¦£aŒP(—eár¹Û¶m“íÅž>DS“„Å"®®$1ñÃÏ6ŒTUÉ6° £E)?]]:„  TUaÚ4Ì›'US'ÕÕÕ^^^ëÖ­ÓÖÖ>tèÐW_}%«+Ý¿ooØÚbãFTUÁÓ7oâøqôë÷áçþõW-µªåŽf>Š¢T‚¸ÈÙ_ÇÃêÕ˜8eeLÇT‹¼¼¼O?ýÔÍÍMºÍ–””Œ5jÏž=111cR*³ 22àí.]°s'„BxyáömìßO>ih ŠQy‡f>Š¢TÈôé8w&&8tNNxú”é€júùçŸoÞ¼)¤Øf^^ÞСCÏž=kii™0pà@)6.‘–†‰ag‡;A||p÷.vì`x¢JSÑÌGQ”jqrBR:wÆ­[ptÄLôŽË—/ðöö–VƒYYY ¸zõj‡âãã»I=‰—âu놠¡dd "¶¶R¾ÑÌGQ”ʱµEb"Ƴg8‘‘LôÆãÇÍÌÌÆ/•ÖRRRÓÓÓ»wïß®];©4+qå ÜÜЫNœ€¦¦$ç…‡CºWaÍ|Š‚|hOvŠ¢¡eKÄÆÂÏ|>ÆCh(Ó€P(ÌÍÍõóóãÕ³eOƒ%&&8ðùóç.../^433k~›IIpqAŸ>8qÚÚÀ£GW»tÍG3EQ*ŠËÅŸ", „ 0>>¨®f6¢¼¼<7kÖ¬æ73|øð &?~\OO¯ùmÀñãpvF¿~8s Bf&BB Å´ªd¼°Ÿ¢(ŠYóæÁÊ ^^Ø´ ™™Ø¿††2ºTQQQDDDBB‚™™YiiiAAÁÊ•+»téòú„¼¼>>ÀÇÇgýúõ§™ Àñã Eb"ÁßsçÂØX -+ ¦RÏŸ?кuk¦¡(Utë±²"éÐddÈâ ÇŽ333 ¨¨¨ „ðù|MMMKKK@ Ý ­X±B|[$((H$5·9‘ˆìßO$EXZ¶$!!¤¸X‘*.šùÍ|%[Ïž‘=@ŒI\œtÛþóÏ?ÙlöÂ… _‰÷.ž?.­«ˆD"qe26›½zõêæ6'íÛ‰½½$ç™›“°0RR"HÍ|Š‚f>Š’9>Ÿ¸»€hj’;¥ÕjTT›Ívtt|»{WXXèçç·yófi]¥ººZ\–ECCc÷îÝÍl‹lßNºv•äÄöíÐÖnr{kÖ¬ÉÍ͵µµuqq‘b˜o+**rww‹‹kÕªUttt¯^½šÒJE""°j?€ŽñØ4IªhÊÍ|E©Ÿ¯¿† &LÀxòG6yÖþ¾}ûÈ.í={öläÈ‘©©©VVV§N²³³ktå娏ü'OÀÎK—büx°ÕwU›úþæE©µ¡Cqõ*:uBr2úöÅ¿ÿ6¡ÊÊÊÛ·o~Í0À½{÷ú÷šjooŸœœÜè´W\Œà`ØØ`þ|Â¥K8ÁÑQQm 77Wüƒ‰‰‰´ƒÃÍ›7û÷ïÿèÑ£~ýú]¸pÁ¢O~õ ÁÁ°µÅÒ¥ÈÍEïÞˆŒÄÕ«psSóœ'Fÿ (ŠRcâ"gÞÞ()»;Ö®mÔ³uttÄ?äçç×x¨  ài3vŠ8}úô€rrrFÛ²eˆ>³ °¶ÆÒ¥ÈÏGß¾8}—/ÃÍ ´8â˜È| \TáZ·“¢ÁãaûvI‘³¹sáë‹o!dllÜ©S'‘ïÅÎÎÎöóóÓÒÒjZDtssãóù“&M:zô¨®®nƒžöâæÍƒµ5BCQ\ WWÄÇãÒ% Ö´0TóIgÎ$ÆÆÄÙ™L›F~ý•ìßOnÞ$|>‘(’gÏž°°°`:ŠRW#HQQŸtðàAñÖï¾û.##ãÁƒkÖ¬>|xVVVÓ¢ˆˆˆW#ûî»ïZ¢åéSâïOtu%k\]IBBÓ®®&˜È|ÙÙoþ‡ÞþcaA$3fÐPrèùçµJ‡4óQó’“IëÖ öö$3³OŠŠŠrvvÖÑÑÑ××ÿôÓOW®\YÑÔUáAAAâ<Ò 'deÂãIV(zz’›7›viµÂÐJö¬%ó½ÿGOlÜØü¥¦Jf>RQARSÉR,®AQöô)ùôSI5¯+WävY¡P8wî\\.wëÖ­~BFñò’ä<‡xy‘Û·e¥ª`(óSÓúr—K||ˆôêÝ)>µË|YYä̲~=™7ŒIÚ·'Žä¿™•™(ª™JJˆ›ˆ–Ù³G¬ªªš!B!ÓSjO ’!Ä  ™^ª¸¸xèС Ο?_ß©7nWWÂf¿étè<ñ`—¶6 S“{{oSñÌ'vú´d›˜ºþ Àtˆõ®ØXbhHâäDrs¥ÛvVV–¸,ËG}ôðáÃÚOJJ"ÆIÞ ÚÚÄߟ4uÖ(õ£™O$"ýú½ùÔsr"þþ’/5ŽŽ2Ú=Ra©Eæ#„ˆDäï¿Iûöµg¾K—˜Ž¢Þ“š*ÙÜÀÖ–¤¥I«ÕÛ·o‹Ë²888Ô¾‡ß™3ÄÉIòÖhÑ‚‘œi]]Í1½KÑåË’TéÓ !ääIba!ù c8<9R—ÌG‰ÈªU’A¤÷w)J1åç“@ŒŒÈ¹sÍo/11Q\–¥ÿþ………5ŽŒ|“ó IPÉËkþE©×˜Î|„‰%ÿÁ¿ý&9’›K<<$GŽ$Ïž1Ÿœ¨KæËÊ"ƒKþsß™Í{÷.ÓÁQTÝ**È”)’×êúõÍi)::Z\–e„ ï¬ü‰Hd$éÛWò¦hÙ’„„4|M=Õp ùÒÓ%_ÿxçøþýÄȈÄÄ„9ÂPpò£™o×.b`@Òª9r„Œÿ&óM›Ætpõ!" ‘L­ô÷oÚ$ä={öðx<ß|óÍ›=ÜE"²?ùäÉÛ¡ukFJJ¤<õÈ|„Y³PKéÌL2hä¥àåEŠ‹™NNT<óOOÉå˜1äÅ BY¼øÍœ^õèÙSª`ÿ~¢­M2n)-mÔSÿýwq‰–   Ie2€lßNºu“¼,,HX˜Z•¯b„bd¾‚bl\ûkH$"aaDS“ÄÆ†\¸ ÷àääÉ“'Ú´iÃt 2pñ"±¶–d¸ˆˆ7wwÛ¢))‰˜™I–Ÿ6l¦¥H$ Àf³ÃÃà !¤ºšDD[[É»ÀÊŠDDÈhíUƒbd>Bȶmõ=ššJºw'a³‰¿?ijM>’WO¿~äþ}¦’ÕÉ|ùùdܸ7Kôê_‡D+íR* "‚p¹ 3f¼Ý{ö왽½½°²E AË–’7EÏž$2R ËT5MBBÂëÝd¥˜ÿ”0ó‰EGssIiƒˆ¦£‘É|ÑÑ’íÍôôÈöíLGCQòrò¤dÅΰa¤°rïÞ=kë` ðõ&$}úÔ7þAÕaøðáoï¦.•ü§´™’“CÆŽ•¼¤ÆWöYYY¬¬¬˜¤©**ÞŸë×ÔU„¢TUJŠds‡wwî\£«[üz¹êС$>žéø”Õõë×ÅKAÞÆf³===ÓÓÓ›Ö&‹¥¶cfÏŸ33lÚ77¦j¢'Ož´mÛÖÊÊJœ•ÌíÛ˜<wî€ÃÁâÅX¼\.Ó1Q”Ü=}Š‘#qçN>‹ÕŠÏÛµ»åêú¤[7¦#«]yyyEEÓQ|ØÖ­[ïÞ½ûþq ©S§.^¼¸mÛ¶jPù3€ÌL|õ.^//¬_==¦cj4eÍ|„`õj¢¢¶¶Øµ ŽŽLÇDQòVUL^¦_¦ VDr‹rø/ý{“€SL¦ŒŒŒNŸ>Ý£G†?E%¾˜ÛØàÜ9üþ;–,ÁÎHHÀŽpvf:,5©Sqú4xyaíZ´hÁtL%UÅäeªðeªðeŠðåÕÒ’ @<"7¢×Ï0¾îÛ×ÚÞžá@륭­­¥¥Åt¶oß¾ÌÌÌ÷ëêêΚ5kÁ‚¦¦¦jP%ú|¯¥¤ÀË ÿü.ß}‡eËÀã1SC)_Ÿ/23f /FFˆˆ€§'ÓQ” UóÉËIªË¿-,É¡¶ÏN£Nœ[}WÞ : ÀÈ÷ï£eKyǪZâââÄ+CÞfhh8kÖ,}}ý&´É–B\ŠÃÞÉÉ€H„ÐP8;#=é˜TQi)¼½á< ˆ[·hÚ£T[v‚à¸+ÿÔäÒk¿V<:^]ò¸ö´À~–&9dYY¡°+VÈ7Rô믿¾ýW]]Ý… Þ½{7  iiª–ùhi!$±±°²ÂÕ«èÞ¡¡‰˜ëÃÄï÷§0)œ7г'v0œ;‡FÞ[¦(¥cáÌõ8«ß?LÇȶ¾A²6l›1âŸcGŒ‹…°0(Ë(ŽBJJJŠÿ,Îy>\¾|yc‡7kP¹Ì'6t(RRàナ bÄ<}ÊtLÊO(Dp0úôAz::vDb"æÍ[E_Bõ.íÝ5Æ <†ä~ab‘_ë9Ýü4YÉ·ØgmÚà³ÏPQà`¹ªZ‚ƒƒèêê.X°@*9OLu?¶ `lŒ3gЭvîd:&eöä \\°t)øûãÖ-ôìÉtL%ÿþ //„‡À<«¡ý¾Òo[óÃSׂm;î݉!!ÐÐÀöí¸uK^±ª”¤¤¤ÄÄDqÎ[±b…Trž˜êf>± pç\]QTooLœˆ‚¦cRB»wÃÞçÏ£U+9‚ðphk3“JQ¥yf*åñcÈÎÆ®] ƒHGߊü¡CI–HÛô{ö³4ÙÀÛw.:vÄ×_C$Â?0¼ò{õêÕ£G¤›óÄT=ó03Cd$"" «‹е+¢£™ŽIy¼z…‰1e ŠŠ0f RSñÙgLǤjââ°u+ÓAP5¡{w|ú)ø| †U« ²“•_ô/”‘vnÎ+Þ|ÿÓnÅúh¼F-í,] }}DGãìYù¯*Febb"‹–Õ ó`±àãƒÛ·áä„/àê __”–2–‹‡ƒ€Ž""pü8Ì̘ŽIýöBB 2€ÏÇÚµxù04„¶6ÒÒ`þ|>Ì£Çó3þ®bk ï¯ÚVë˜öä²8’çuóÕähIº€ïÌV35Åÿþ (ÅT;5¡™O¬}{\¸€p¹Ø¸½záúu¦czC±ævVW#0ƒãñc88àêUøø@AbS-II8u ÷îa÷n¦C¡Ì˜¹s±v-ìÞGЫ€ìÁ 7þË¡ž%{ô!½Ž“x¸:¬íØ´Z²:N®{éð‚hÝ·naÿ~ùü*‰Ëå²ÞÓ¦M›¦µ¦N™—‹€$$ S'¤¥ÁѨ®f:,sïœ B€¤$téÂtL*ëÇ%?,Y‚ª*FCQ[™™ðóÃâÅ0s&z÷FïÞ`a "­°Š3SK+ ‰…3×õ¸ž±=çõS»¨5A IDATrtòâquÞ|/¬ù-VOK–À¢E¨¬”Ó/¥r¢££cÞ²lÙ2666MlN*µ´•OYÙ›úô!wï2׿±¶¶f8Žî(KICRy]Í Û¶1ºÉÌ$„þ‘ìwÆç×x¼ò•èÌtþ6›WÛÛ¿º¹ª\$¨ÙÀÍ{>)ª*yg³½Å‹øé§ŸÞª®&vv aa2ø5ÔNff¦™™™¥¥åÓ§O›Ö‚šõù^ÓÖFx8N‚¥%._†ƒÂÃÕ}‚ÝË—?¾¾()»;nݰaLǤâ^wøÄ‚‚h·O^ª«1p :uBv6>þË—#9ººoŸR&<áÎzNÀ3` Ù¤ë0_‹Å©ÙŒ±=ÇΛ§¡÷Îòþ .?ÿ ?ÿŒ¢"™üFj£¸¸x̘1¥¥¥'Nœ°´´lZ#êšùÄ\\šŠ/¿Dy9æÏǨQÈÎf:&†ÄÄ [7> ==lߎ£GѪÓ1©¸øxœ9óΑDZcCѨ‰ÊJlÙ‚ ¡Ö­¡¥…Û·`áBØÙ½}â½}UÑü’Ç"£Î×czm†Ô^Ü¿eN穚 ºô¸qprB~>BC›û[¨1@0a„ôôô½{÷:884¹õÎ| ±köïGË–8u 8r„é˜ä«²óæa̼x~ýpû6¼½™ŽI-üôS-þ™vûd)0_åËà÷ßñø1Fެqа‚$ü¯ìR`¹°>ç9ª§o]ç礆K«eÍ™_µôùÄ~ÿ]RÏìÉ“fÿ&jjÖ¬Y§OŸ 3fLsÚQûÌ'æé‰›71x0òò0n&NDa¡œC¨óÝ"S·o£G¬^ 6AAˆ‹C»vr @]]¹"ÙÜ©†Ç±gÜ£QmøáÌœ ¾¾èÖ C†€• jœË"Šñ,}p¤š£ÅrþC»_ˆ6§a=ºqt„»;ÊËi=³¦Y¾|ù¦M›æÍ›7gΜæ¶%Å»ŽJO$"DG‡ÄÚšœ?/Ï‹?zô€œ®'‘°0¢¥EbkK’’ät]ŠBÈèÑïÌmyû­-©®f:>Õ•E!™™DCƒp¹$;»þÓŸ^¨þ»{Ñ6›Wûç§¼7›¥Á¾ÿþ{¿þúk-¥§ Âá””&·¯ž<Èb±ÆŽ+ ›ßíó½E¼àýêU|ú)?Æ!˜7O5g!ggcäHÌŸŠ xyáÆ º‘º<]½úN¡ýüh‰Yi˜2íÚ!%ÖÖX¹II07¯ë\"ÂõЊ3ÓJ+ ‰å@®ë1=ãnïÍfi0RÏøM§N˜>B!›Ü¾ÊÊÊòòò244ôööŽ=ùŸ .4±Åæ'OT]M‚‚‡CÒµ+¹qC×”_ŸïØ1bbBbdDöï—ùå¨÷Œ#éÞiiÒªH` 16~Óí«ªb:Je$‘#G$oØÙ³‰ŽÙ¹óƒO*Ïš,Yºòg}ðà·ß~«ýáœÉ¡3gš{%µqõêÕZó—¥¥eÓ¤™¯nII¤C DMýhyd>>ŸxyI>\ ËðZT®]#,ÑÑ!ß~+~35%ÉÉ!ÅÅä·ß$_K6of:Pe´bˆ›!„ääÜÜ>#ï¦à@ßâm6¯þv(zz^:£ÌBBBê~û “&€—ºtxÖŸ©)>Tì8mkåÉÏù¥ÏE­8nÑz–ƒj_º } ¢uk\½Jë™1…f¾zéè <1107GRzôÀÆ2º‘ÝÜNº£¬Â°bÖ¬AëÖuž£«‹… qö,ÊÊä™2o7-"${÷âöm˜™áÎøú~ð©‚rÿmÙ•eÂ*ØMåܧ§k.µwćßËzz’*߯š3 ýøk€‘#ñÏ?øì3Ã×£Gãùs¦cj0º£¬"árkéi¿îó½MW÷ý)÷Ô[þ÷?´osç``€°0ÄÄÀÞ¾O-y,Š_úðh5W›Õ•Nï mNÝå¦eÅÇvvxôr¿6E3_™˜àÈlß}}ÄÄÀÁ‘‘LÇÔoï({ø0ÝQ–RzgÎàâE06†HñćiÓ0rd÷yS}Ü•_&Ô·f:¤Ûþ³Ú6Õkžßp¹’Z?ýDë™ÉŸ”3Ÿt7’P8ÞÞ¸}"7îîðöŸÏtLux{GÙÑ£‘š ¦c¢¨æÙ½..’õsæàþ}4üÙDˆ+KË/Ì.«æëQn'ôZÚ5}邌/©g&®)CÉ‘”3Ÿ”7’P@668waaÐÔÄΰ·—|U(5v”=q‚î(«Èjí¤$*+±f FŽ!ðð@×®1 И–òX`Dý€TU++“'›ÜRÎ5Á~Çâm6¯öõ*z‘,ó9 ,°bÅŠíîNòõ×2Šz‡¬îóIe# …Ö­’’BŠž=%Eß›Š4n'ÝQV9Ñ>_-V¬€•‚†V®ÄÁƒMÞ3+uCåÉÏùe/D¦=8®‘zf}d¾t¡qïåÐPp¹Ø¶ ©©² ‹z‹L2Ÿ´6’PtZZ A|} ‘ˆ™`6nD¸r––8u !!ÐÒb&Šj²[· ®GelŒÒR\¾ &`üxp}ONPF.Î+»ZA„èæ§9rŸžNkÅ›Ó÷ºžÙ÷ß3Š‘Éë@ZI(‡~ýpã||PQÀ@ .ï!{º£,¥ΟG÷îðõ…H„)Sðï¿øã&7ö*CxÂÿ(²š«Ã®Ó# –}ee¤Ñã7ÁÁÐÕʼn8wN†aQo‘~æ“æFÊ¢E DDààA´j…³gao/»ï5Ñe•ŸZvŠDؽnn¨ªÂÀèÝ[²‡Î›ÜjfTu”GiÑC‘aGŽëq½vc¥¿tAšÌÍñ¿ÿ@` º¾äMÊ™ïСCcÇŽ]¹r¥t[VãÇ#5nn(*‚¯/<=ñò¥ /Gw”¥”Zi)**ÀfcåJœ8½{Áfãòe,_]Ý&·* iQyÜœ2A±£1ú°®A{yp6åžýÿýÌÌpõ*UXÔ[¤y³·ÆF¯kii 4HŠR\ffˆŒÄŽ˜=">ýY ùÞ¾/¿Dj*8,^ŒÅ‹Á­ó¿²¨¨("""!!ÁÌ̬´´´  `åÊ•]èä…¡Ž}¾-[°p!–,Á¼y Av6¾ø¢ù­–åˆâæ”ç^°¹è³L»ã$ù—fš–ùôô°x1æÎE` >û >„Ïÿà3îß¿ÀÖÖöçÕØQöÒ¥úO?v옙™Y@@@EE!„ÏçkjjZZZ d¼õÕpmÚ€{ö,//O ñPTÃݹ;;Lв2Œƒ„ìÛ'– R7Tžþª´¢€˜;qÝ¢õL{Êk×…ZÃiÚ % üò ,[†âbÄE½¡xs|U—‹€$$ sg<|ˆAƒجg"#áà€ØXaÿ~ìØ-ê9=::zöìÙ½{÷þí·ß^ìÕ«—ŸŸßæÍ›[׳Y%_Ê7ÚÙ¨XÅèÑ(,D×®è×nn(+› ''©ÄRULÎù”]­ "tóÓtÙ®«ÕRVÅYdÎÓýú!?+V0Šª“oS-•—“€Âf€ôîMÒÓk=«¾ÑÎÆï([\\ljj 66¶™áS²&.Q’•Åt Až?ÿði••¤¤„BFŽ$oP.í1ö‚tÁáAÅÛl^íù¸(ë´¢lcïïï <<¼)O¾x‘D[[=†¿Óˆ>_QQQppðÞ½{e”ƒU–xÁû©ShÓW® {w„‡7â[s“v”]³fMnn®­­­‹‹K³‚§dO™ú|ññ˜3çÃEŽ…d/‚E‹°bfÏЄÕèõ¸·¿*Ê_œ)2êÄsLÏj˜b/]h þýáæ†òr,[Æt(ª¬A™¯¼¼<<<ÜÎÎnãÆîîI5 †ÔTxy¡¼óçcÄ<{ö§ÔØQ6!¡á;ÊîÛ·M{”4åäàË/Q]]gæ{ñGŽ@›6xþII ýûcÁèëK1Q5’•_ (V¢ÃDÞ˜cz-lèÆ if%ÂåËÁåbËܹ#Ͱ¨·|àå"Îy¶¶¶óçÏþüy`` 6Ýà­É °cöïGË–8}ݺa÷î×Ö|·<}ZsGÙ^½xÊÊÊÛ·oèÖ­›”JmUWÃÓOž€Å‚¦f-'äæÂÖ“'#'={">qq Ü3¯QøOEÑãùW±5Ð÷Wí~¡ÚœÚÂQb;cêT…X´ˆéPTV™¯FÎ`aaáãã#ÇØT”§'îÜÁèÑxõ S¦`âDÔj‰°hÆÇÖ­Ò]«Pƒ œ$ÿPþàH5€Ž“x½ƒ”f§Ô2Ÿ†~þŸŽ¥KáåUÍ&ªQÞŒ°Ùì‰'N˜0¡ÖüwåÊ•ŠŠ ')RS¸\üõf΄¯/Ö¬Á7ß”çå…=ZúâÅÇ€HG§÷¡o4wkÝZY°P#²‚öîýBu”å#€Rb[¶ ž/»‡!- GŽ cGY\¼$KtaVYÁ!W›åø³–í8uëóôDX’’ðûïtm»Õì7ˆó_jjêéÓ§{½»€lñâÅr LµÜºGGxz€ƒ8ñÌïcc«Ö¼xÒº5 `OŸŽ–-?ž­i=R£fÚ@ð‘'Ïy%M{ªFû|×®}xxíßÑ»7bb¤~ñ¬SÕÇÇð îõÛ²GÐUº´'µ> !!°r%ê¾E5V#fÆ KNNÞ·o_×®]ÅG.\¸(• ÔDQ-’d;ñž“qq¨ªÂ§Ÿ"?7þý÷߯ {ùò¥ßgŸ¹‚ÃïËÌbÃùí–]j¹ƒrÿ`ÕÙé¥Ùñ‚ú‡C)ª¹bcáí OOxzbäH ''ôè?Fûöh×FF02Ÿ77üñ‡´.K„¸Zq~fY5Ÿ´¡á¥×²«ê.]h àêŠÒR3Šê`‘}Õ‰D¯Ç?‡ vúôiùD¦”ÁÙ³ˆ‰Ah(D"˜˜ ¸ÁƱ±èÛ÷õ}‘àààeË–B‚‚‚‚E"üô&Lx{;æò05Å•+8|XÊ-«šù>¤ ¿þ ÐÕ•L`!C‡âÅ üùgCÚ8vìØàÁƒ_¼xáîî~áÂsssÉ¡¡àï_Ïmµ[ÚqªßË|b<}–Ý4Íqqú×é˜|Ê)Ï'ÿ„Wp,Nø_Ù« aã~YŠ’—Ìèêh~Ñ‘a¶k¤^ûÏTb_Y™Ò×—ì[´hÑ;õ䍯£™¯6"’“ñÛoÀb!8þ‰—/Ñ¥ ¢£‘– ¨­´÷û‚ƒƒ=<³fᣑM›¤ß¸:Q©\sUU!6•• îîX´))02ÂÊ•8y0jþÛèƒÏÒ¥K9NDDDxx8çí:‡â;|~~uîpýmSVï mÑglÏq^©3î¼~7?Mž+÷šðÜŒ²ÃƒKÒ¶V ÊÔæÃ•RTå¹$öËÒ´mUlz/Ñ´NGC—Nâl0q=3ÁÁ(.f:%F3ÀçƒÏŒ³gÁáÀß‹ÁÐæÌÁСà6n¾Yqqñ˜1c6mÚÔ¢E‹'NÔÜÔ÷Þ=;m톢Õ6mÄ„ž»G€Ö„Dý¾¿jزK‹®,«8àXreiyi6]¡XÔ§Ï÷ü’ rtIζ)køn]»iª¹tA†}>'¢o_äåI±€€RûÌ÷ë¯01‘ìº9t(:u’ì(ýÃøåXY5­Õ¬¬,ggçØØX++«øøø#FÔ<#, "¾ú ²Ü6]C—ÕqÏ=VÈfs'nU IÛVuh@ÉÙ¯Ks¯Ó[€”¤n¨<í]Zñ’˜÷ãŽÖ7ë­ÜKê!ÛÌ÷ºžÙÐzfM¦–™/.âûï MTV"=-Bzzö@¯áúõ뎎Ž)))Ÿ~úirròÇ\óŒü|lÛ6[\®LÖXlX Õ¾K×-J¯ã$›‹§ç1ø'Æò®"4R2VUBÎù–]­ "tóÓtÙ¡«e¬Š}=¹0cÆ ´K—2вR›Ì÷â–.•ÌŒb±pñ¢dáù¸qÈÊÂêÕ;žY«ãÇ4èùóç®®®qqqµ/ü_¿ee;:4ÿРײ §ï¯ÚãZ|2OSÓˆõ2E˜ð]ù~Å·Â**_©ÁX›¢RíÑÎWÂ(wþ“ÓÕ<}ÖZ,U¯Ä)Û>ŸØŠàr±y3þýW†WQ]ªžùnÜ@XTVbéR¬]‹ÊJ89a÷nI)==I½iX³f‡‡ŸÏŸ3gÎÑ£GõÄkÛk(/—”+«cõº¬i·b9Ì×B3êÄ)Ï%ÿ„Wt*IZT^tŸÞ¤¤éÑñê(ÒâG"ÃŽœ1Çô¬\èÒ)±³ƒ·7­gÖdª˜ùÄkŸggüïxö ÖÖX¼;w‚͇ƒÉ“ad$Åk …ÂyóæùûûBÂÂÂÖ¬Yék»ê;‘› GG8;K1€ÆB{RoÔ]›ÑÂJ’ñwÕ±%±SJé*9SÉ>Ÿ¨I‹Ê/ú— ÊH;71Gt[´SÅO›ÚÈ£Ïà§Ÿ £ƒ£Gi=³&P¡›Ì••`³¡¡>}pí._FïÞ˜6 \.D"²Û×±¬¬ìË/¿Kµ;NR‰Ò,ŠÆÂóæá·ß°`’’š_4\­¨Ê·°eË`jŠ£GÀÉ ööxõ Ö­Cxx“§h6ÄÓ§OûõëwôèÑÖ­[_¸p¡¾´àÄ ddÀÖãÆÉ.¤&зf÷ÒöLÖï½DKׂ]&LZT~йäzhÅÛ;%QÔe'N¸ñ_¦õ,Ù£é©aÚ“SŸ@@ZµÂåË8rDæ×R-ÊœùΟÇèÑ’É)úúàó‘’¿ÿŽÛ·1|¸B¸uë–££ã?ÿüãààpíÚµ^ïí·P“¸Ã7oê e”¸Úø‹úC6ë˜öàT¼$©* (‰›]–‹Î••í$"Ü «83µ´²X8s]ëÛ+âë\uHîó}ÿ=­gÖ(Ê–ùrrðûï€W¯#ÙÍuÚ4dgKÆ3¥1E³!¢¢¢ú÷ïÿìٳѣG_¼xÑÒÒòOHNÆÅ‹06Æ×_Ë%À&bq`5TcÔAI!4"Bftu”?Æ“Ÿ]MWAPµª*"ç¾)ý'¼ŸÌÓ¶MWÓHMÇßä×ç0klm‘‘Í›åq9U¡$™ïÆ ìÚOž`áB,_‘#F`ï^DE€¡!ÌÌäÑúõëÝÝÝù|þÌ™3;¦ÿßfëõYµ üü^ÿŒYâBhõ?™§©iÈʽ&Œ›]vdHIê†Êªbåï¡( èó¤ O¸óŸžð XC6é:ÌWý¥ Š‚ÇÃO?@p0JJ˜ŽFi(pæ ‘œ 99èÕ ß|>=zÀÏë׃èèàóÏÑ¢…œã‰DóæÍ›={¶xçúõë¹ ée>x€C‡ ¥%ÙöAy蘱æÿWí#6ÝžªáÞ¾ªh~ÉcQK;Žë1½6CThÞ\“ȵÏà‹/г'rsi=³†S¼×hy9x<°ÙèÜ÷ïãÞ=|ôÆŽ…±1JJ §×Àd¤¬¬ÌËËëðáÃÚÚÚ;wî?~|CŸ¹z5„BL SSY(+\VÇI¼Ÿó^$ þÝRùô¼ m[UúŽ*ËAÜ.Ó5Íï…DÉž°‚$-*p¤@‡Ïy}–js4™ŽI ±Xøýw „?þ€ŸZ·f: % `}¾ `b‚¸8°XèÓíÚáÉ8r›7ãõ¶v ɰ¨îz IDATÉÉ2dÈáÇMMMÏ;׈´÷ò%6o›… e Ì±Ø0wâýë¿Bh<Évð'ÜèvðM§¤£ü'¢ÏÒGª9Z,ç?´û…д'!ï>€1jø|Ù­ÝR1RÊ|W¯6ý¹QQpq‘ÔŒÖÔDi©dsÃ<|ˆÁƒ¥a³¥¥¥õíÛ÷òåËvvvÉÉÉŽŽŽxrDÊÊ0j:u’Y€rÕÒŽÓ÷Wí ú=´tZ³_¦ “•êO·ƒWÏâ'Üù/S…zVìQtmÇ©ÝÒ…z0ù„†‚ÃÁÆHK“ëu•“42_@jÜSòò°aþþ²³qæ €Ù³ñ𡤺f­¥¿rþüy''§G <811±]»vxrE…déCåÊdG˘ÕÍOsüE}ç?´:sÊóèvðM¡\}>"ÂõЊ3ÓJ+ ‰å@®ë1=ãnt6‹°·‡—„B,^Ìt(J Ù™oÙ2,_ŽŽtrFbbàúuÌœ‰ÐPøì3lÚ„¿þ 4*©ÈEDDÄðáà ½½½Ož?ÿ >ŒÄDy_ZÙ4/óýð‚‚ sç:Ï!wïÀ½{èÔ ÞÞ0d¦MÃ?€˜˜`Æ ™nS×dâiœ~~~B¡0$$dÛ¶m<^#GuÁÊ•0¾,"T(¦=¹×éxœÕ·›ÊãêH¶ƒ?2¤$mk¥ œ&@¥—KxÂÿü’@Ó5ô/Ýn~ª¹¯¬³´Äܹ°`ÒŒ!0¤©™O$‚Ÿ~ýUò×.]jž @u5:t@·nÈÏG‡2& ¤<¶l§§"ך+//ÿâ‹/V¯^­¥¥µoß¾€€€¦|‰;y©©°¶†§§ bTDâBh/ë÷^¢¥gÉ.Î]YVq OÉ•¥å¥Ïé*ˆZ(ÅhgÚÖÊ“ŸóKŸ‹Z9pÜ¢õ,ÑÙ¼ub¬Ï 0ÆÆHNƱc \]y4)ó‚ùó!ù«©) ß9á»ï`f†”hh C´oÌL8{þ)ÝMd$77wèС0119wîœg“óÖëreòª,£ 4ôXvÓ4lj ¡õ䈷ƒ?< $nvYÞ z P™ÊIü·eW–U«`7•7rŸž®¹‚Í §^34”Ô3 ¤õÌêÑøW°@€/¿Äš5oºkâ_t4<0`À¥K—lmm›Þ–øŸRÛL¥ýWííà:•ÐíàÙã˜êã®ü‚4¡¾5{Ô!ÝöŸÑ}e•'YÕ·d ­gV—Æd>ÞÞØ¶­æñ7 áóÏ&™PÛ±#ìí¥¢<íÚµkøðáS¦L‰mÙ²eÓÛÊʾ}àñ”®\™ìh›²æky&µpþCÛ°»,GD·ƒWL"®,-¿0»¬šO¬Gi¸ÐkiG—.4Ã}>“&¡GäæJjSïip櫮ƤIس§–‡òòàë [[Ì›kk)'O„àà`oo着ª   ;vhj6¯"ÅêÕðÅøàj†£ Ûq<÷SúÃwé¶Â”«ûvðŠ6ÚYžGb§”¦m«b±Ñ{‰Ö u:zŠ;ª…¸ž€+ðâÓÑ(¢†M»¨¬ÄĉˆŒ¬ó„Í›¡©ùÎÍ?¥RUUåãã³}ûv1uêÔæ¶øê6n‹… ¤ŸJbÁ܉kîÄ-~$JßQyoÝ^!ä^ÆÍ)+{!Ò6a \£cÖG½ffIó}>ƒaäHœ<‰Ÿ~ºuLF¢ÖçÛ²™™Ø[gÝ:%­Q’ŸŸ?dÈíÛ·ÆÄÄH!íØ´ %%pqQÒQ_yjÑŽÝ;H{ü…ÐÔp;xÅéó¥n¨<ù9¿ì…È´Ç5R¦=å¶|9ØlZϬV Ë|3gâŸÀç#3§N!, ~~<¸fQðU«(‹(e'##£oß¾‰‰‰:t¸råÊ!C¤ÐhU•dï\åü*À­–’Bh×é´rx³|ÂÿÊ ÓéP™”‘‹óÊ®‡V!ºùiŽÜ§§Óš.]h"…èóá¿zf~ü‘áHOc¾Ó±X°¶†µ5†sðÕ+ܽ‹ÿÅÝ»HOÇ‘#ÐÑÁ’%RTâãã=<<^¾|éìì|ôèQcccé´»ož=ƒƒÃ;ÿPT°5`3ZÃf´Fî5AÚ֪ǧª©~p¤Ú´'Çnš¦õ ºß©,¼Ê^˜YVôPÄÕaõûM»ÝX:‡SUüò À¡CHL„“ÓÑ(ff¢OôéóæHUQü~{öì™>}zeeå¤I“¶nÝÚÜù,¯‚+HuPMbÚ“kÚ“[’%Êø»*cOUî5aîµ2}kvÇ/x'óx-ýÕÕ(ÌŽvfFU'þ_¹ Œvä úSÇ =íê5—¢ôùXZbÎ,_ŽÀ@ÄÇ3‘Á«œÇSü´Dýú5Ja÷ÔU ¸í½‡EXtZfl^›/¹»6ïßî™·Väf½Õ‰G€J%áÆ¢Ü+3sD9Œí ƒA'Í(í)„e> ¢zu„‡¿Ÿ™:<^fƒÎýE …žžž+V¬Ð××ßµk—‚ÿ‚J·+›94e¤fû‰FC®XôÞiZ»»¾0K¶Ú%ÏìÄë"¶£SVÆ|9$çGe??,àê£ëï&½6›ê›ªÇoj¢XU«báBðö–m§,'`ýzV‚bne¾´´´ìÞ½ÛÒÒ288xÒ¤I î :çÏÃÒS§*øÎ:Oºšë3·@óÆßp¸ÿò„@¢ Pu¯‹f}¼#2µæö;lÖlíH¦Hê5æ0k5*f?3ܸÁRL,Ó¡Ì÷ßÿõèÑãÒ¥K666ááá...ŠïCúÊÓUª(þæP½¥^u¦Ã">o„öH>/÷ßnt|ù0xô7ÿâøì¼¦vw}^°yÍTº í ±bøø ;[Ö‰ÿû?ä屋t%óݾ}»k×®?îСÃ7Z¶l©ø>pè hm‹ ˜Ôà´™cìq³Jÿ™Tm¦ÙÇÁ«l¶SÁ„Nι»6‘ åT£¾ûÌŒ«©Í¸D‹¨Ý˜ÀèÑh߉‰²Í„³³eG¥ææ²;t"ó=z´gÏžïß¿www¿|ùríÚµ•ÒÍ–- áázõ”rò=CéFh掙Õë­/âåIáéþY:»Z)RŸ‰Ï¸g½ VáôÞaÚÞÛ˜JDâæÍ›IÙë­233_¾|©‚xŠÇáÈÖœÿñ>|€—ž?€œÖBb•ög>ŸQ£Fåååy{{?~ÜÌÌL)Ýdfâï¿Áá`þ|¥ÜŸ”ªfý>»Ì¾µ°Ÿ`¨oÌI¼.¢ãà ŠýGpÆ=+ã?‰•Þ Óæõ]hù•Âr£F¡E <|¨þUüº&ù¡øÉþ«¡ôøê­ôì'6r7TŸ§\:áömܺ…ŽyÛwWEWçäðSóz\§­¦Õ[©ÍXëðùü&Mš$”œcæÏŸ¿víZU†$“’‚iÓðÏ?%^`m­›Çiá¼ÇÝ»w»téòðáÃvíÚݸqCéi…õóÏ”öÔô8ø!a-§ZÊŽƒ?áœùèo¾ ] ?ö`$¸»6ïâ„l~*S§§¾[€9¥=¥222ZPòfýæææ¿°uZYµj8zgΠ¤e}ººÂEÛÆ|£FÊÎÎæñx‡RÅ#åË—áìŒÚµî‚F”@˜ÍÄcvñÓ_J˜q6pð4²lÌæG@ÅŽùøiLøÜœ„0‡‹v¿·œbú<¦|yyyMš4yûöí—/y{{ûúúª>¤B>~ÄäÉÅl`¦¯¡€X¦Uc¾7~ÿý÷ÙÙÙ3gÎ9}},[†ˆØÛ”ùÔÛÉ“'“’’®>\1**ªK—.g>à˜™í@‰/O dõÈú/XV¡†^ŸÊJy,¶hÀp̬ñªØc“±±ñâÅ‹¥_[YYy{{³Oi:t@TfÏÖÍ̧1k;»téiii™œœ,}†wæÌ™‘#Gfee 8ðèÑ£ªÞ(+ 66HIQ|Q™ñ’'{ù±ÿE9 ®ýxæ# •qˆ]×®¸y7n K— ¼‹ãÞŸy¶óÁ A?ƒš˜Ójöåææ6nÜ811qÑ¢E«W¯f;œrHÀÕ˜!¢hÆøöíÛ‘‘‘ÒÓÓ£¢¢lÙ²ÅÝÝ=++kúôé§OŸfaC¼½{‘’‚o¿¥´§•,l¸–›xÜ´è´Ìج73^rë·¼:«Ëqð¹IÌ…1Ùþæs¸hïmì¼Í”Òžš011™?~•*UæÍ›Çv,å£{iš’ù¶oß.ÿúÊ•+^^^3gΔ.ãܲe‹¾¾Ê×°‰Å²Ã>4å/7©C ŽýD£¡W-zï4­Ù^OIÇÁWt…˧{â ^Öû›"“o8®¨tAíL™2eÕªUÕªUûò%±Xìää$ÝÞLÞxãÆ CCÃ>}ú”çÌ¢0ÛùñãÇ ðù|é·µjÕzÿþ½©©©¿¿ÿСCÙ‰éßáá{{<~Lû¶èŽb7Bk8Øûu½ºuȈ@×®e_üdÿ®ožX€íôœ¶˜šÖÒŒ¯D.11±M›6¦¦¦QQQU«VMNNnÛ¶­P(ŒŽŽVé–ÖºMþÙìß¿_žöHÓÞáÇYK{þø¼¼(íééFhÒãà«Ê6BSÙqð¢æÚÏ9·~Ë `?Á°ßasJ{š¨víÚ|ýúõĉ%ɸqãÞ¾}{èÐ!J{*Ũ7±XܨQ£/Ã666;vì7¾|‹H$êÕ«—Add¤¼1""ÂÀÀ wïÞb±økc g¦V-&/ïkoE4–0[òìÿ¤KÆ^Û´½¶iûíÒ®ýœúLT‰[uëÆÌõë¥]“ú\|²OÆ^Û´é/O *4QË—/УG¿ýöÛáèuŸíáéSœ> 33Ìšõµ·"šÃEíîú}vÉ6BÓ3ú||Ÿ _Ê ‰·Vä^™™#Ìfl HÎÏÚk›æß$-fw#QVØDÅrssÍÍÍ7oÞÌårÝÝÝÙŽHç¨uæû¹ð®`5kÖôððزeËãÇËóv±XÜ¥KÎÎÎ x¼Ç0ÌÇŒ‰ Ãå2ÏŸ+ànDK‰Ì‹ãüÓý3¥ùÏ¿iÚåéÙï•ø°ØÌ÷îºðHûô½¶iG;¥¿*=h¢B“'OpàÀ†a¤{¾¬[·Ží t‹ú>çËÉÉ©W¯žžž^Ïž=œœZ´hÁ©ÈZÊçÏŸwèÐ!33ÓÆÆ&**Êêë7•^±>>øî;œ<ùµ·":àãÑ“=‚øóeÿí·ǵkèÑÀàÑvþ½?ó1jwÓï¹ÑÔ¸:-!ÖGŽ5jÔ?þèçç@,÷éÓ'"""<<¼S‘SˆÒ¨oæKJJúðჃƒC…²\^^^—.]^¾|éëë;{ölwêÔ©¯ (766øô©À¯(BÊVd#4óú\» ›24´”ýÅ.˜ù™Lø¼Ü7…à å£v¿sè4u-Û¾}{[[ÛÈÈHiã»wïÚ´icff&]‘Çn„Š$C5§ÅUœúf¾¯4eÊ”;v8p`ôèÑK–,Y½zõºuë~þšC¶oÇÔ©èÚŠ “è aó☠f—@ºùYÁãà{öĵk¸z­¬ÅaSs2â$†œÿ3©ß× ÌÛ¢vÄb\º„ƒan޲–(²E;3Ÿâç$ØÛãùs;†aÃ.ÑŒ aÂ'{ÒÍÏ8\ÔuÒßùÈèÈ-ýà?„){sE9LÕfzΛViHk8‰¦‰ŽÆþý8|‰‰pü8† a;¦âiaæSÊ|ÂéÓøî;4i‚§OÕvüN4Èû¢˜=‚„KBF)"n5 4p5èþ§‰¡=Ø#šãÍ:„ýûñøq~£±1’’`fÆ^X¥ÑÂ̧Ò ©M›0s&Û¡-Á0¸ÊÜÚÆçÞˆ$¨bÀtñ1i>–Ø#"='N`ÿ~\¹‚/÷Ú4AAl„U.*?å@ݼ‰k×ðÍ7˜4‰íPˆÆKJÂ… 8çÏãÃ`l¡g´ªNGÂD¬ÎËK–Ø72²¢1QWÎÃÁƒ ,íT[O…1Ue¾rH4u*LMÙ…h$>. (!!xõJÖ¨¯¸¸ OoΛ Æ¶òm!¾¿ÿd·ÀnŒ¡ýD#“”ÿˆšÉÈÀÒ¥8xÉÉ¥]Æá¨yæ£Ùβ¼| ;; >5k² Ñ$11 DH""“#k¬[ƒÁŽ{£zõü‹OžÄü1âÞ¦ü®B®>ò ZN5ªÚŒž+5#ãúuœ>S§ò?ÊÔ±# @¨†(ó•eöllÚ„„ŸÛ¡ ‘óçRhxghˆž=áâ77´hQâ{OœÀÈ‘¨Éb¾ÕKXpPÏY¿Õ4ãš(ÿµtó&†Ç›7…W®Ä’%,T.”ùJ•œŒ —‡˜ØÙ± QS ƒ{÷‚À@DFBôù´ö ðÝwàñеky׸?Ž‘#!aõBf`Mþ“ÝA& f½–S*t!J—•WWܸ5ðéS~{t4Ù «l”ùJµz5–,›Ù…¨ÔT"(W¯âÃY£±1\\ÀãÁÅÅ,Y¶ÿŨQ‰°r%æ{1Ï íàKO¾­ÚL¯åœOˆäåÁÍ —.ÁÆçΡcGHÌiÒ±±lWÊ|%Ë˃ >~DXœœØŽ†¨‰²µ*ÑÑ‹eí²l×½;>‘VÞ±cøáˆDXµ ‹C”ÃÄ<Þ)È~'`^—ëàiØt¤¡¾ K„B †€Ôª…«WÑ´)ÆŒÁÁƒ0gþú‹íøÊ@™¯d»wÃÓ;ãæM¶C!,{ûgÎ $aaHJ’5V©‚~ýdë3+7¼+Å?ÿ`ôhˆDøýw,\â¶ Òž‹Yqš3¤Â±#FàøqT«†Ë—ѪÉÖs^¼v,e¾H$hÑOŸâðaŒÉv4„®^•=½‹‰‘5r8h×N¶V¥Kè+sÖñèQŒ ±kÖ`Á‚Ï­ Þ„ ýÍÿxG @ß”Ót¸A‹ÉFfµi·3¢ &M¾}°°@HäûA …¨[>~„¡ºoÈ@™¯ÁÁ4áùsÚ®L§ÄÇãÔ)áÆ dgË­¬dÙ®_?X[«.˜½{áé ‰¾¾ðö.ôÒÇ;¢‡Ûø a"ÈK ¦WmJù(Ù¬Yؼff¸pݺzÉË II²9OõF™¯}ú 4ý…9sØ…(]^.^,ZiÎå¢kWÙÓ»6mXûü³g~ü ƒõë1{vÑWÓž‹ýÍ JDŸK ¦×lOŸÕˆr,Y‚Õ«ad„À@ôí[ôÕ[·‡#؈¬b(óçÞ=´oªUñú5,,ØŽ†(ËÝ»²Â»ë×ó·aªSnnpq³3¾ù†Õø>Û½?ý†ÁÆÅo›õV³3ÿ@* J±f -‚¾>ŽÃwßsà 'Gmw©.Hç3ÃàË“oGÆ¡Cðö†¯/1%JOÇ…  ÁÅ‹ˆ‹“5 W/ÙZ•¶mÁU¿)Ã]»0y2›6aÆŒâ¯á§2OöñŸú ¤%Vvz-&sŒÃv4_Kç3ßÚµ˜5«Ð†œññhÒ\.ââP§{‘…‘VšKkï –"Ô¯àægg˜›Wþþññ Dt4ÂÃѾ}¡ÇAA5 cÆ`Û6<~ŒãÇ‹çÏñú5^¼ÀË—Xµ W®@$B¯^Ø´ uë–ØËΘ<6oÆôé%^V´¢×a•@¯ãç‡)S`×.LœÈv4ŠÀ踉™Ñ£ µÌËÌøñìÄC'9™Ù·ñð`jÖdÙFFŒ‹ ³~=óò¥Â:ÊÌd^½b~ü‘+«B/ýû¯¬ßW¯˜œæ¿ÿ˜îÝ€qvfNbúõcüý™]»˜Úµ€qtdD¢Ò:Ú±ƒáp‡ÙºµŒÄBæÅqþ)×̽¶i{mÓ·Mú+7/UòµT¢ƒfôô€Y¿žíPFç3ßôé ÀlÜ(û65•±°`8æáCVÃ"•$0/2ÞÞLûö —›ŸðìíooæâE&;[Y]ø ëëõëBí£F1“”$ûvøp`<<˜E‹ÉçLäï/{ïÕ«eô²~½,ùmÛVŽ˜$ÌëAðPYþ;àé““õN\Á?ÑaŒ0Ë—³Š"éü&HÒyιsѲ%œ±c23ѯZ¶d;2R FHBCóO±°@ÿþʪ4ÿRÍšhØqqxþõëç·»»#66ÿX†ˆHMŪUù˜¥¥Àââðí·¥õâå†ÁÏ?cútp¹²ùÏqP¿Aý>òˆ'{Ϩ‚”˹s6 B!¼½áãÃv4ŠD™ÏD" ŠðplÜóæ±)>׮ɞÞÉK8´o/Ëv=zÀØX¥!ÙÛ#.¯_jOuvé’ß"bøp…FãÆ•ï×Ç V®Ä¸q06.~KŲ[qPÐÐÍ ÕtcË&”ÿ´Zr2úõËh×AA±÷æ× ÌW8óq8X¶¬è’sR.`èPde¡M›Ò …¸rEöô.* ‰¬ÝÖƒƒÇC×®üNºÚû÷èݽ{}544ÿ>`Ü8deáÚ5”þö«Vaøp;w÷Êߪ` Ä«€%3k´ÕΧ>º.5..xø8w––l¤t:¿oç;èØQöµ‘¶mÓ’]éTËÏÓ¦Éf)'M®]E/xógÏ"0—/#+KÖhnŽTWi®oߢ^=¬\‰%Kоôü9ìì`i‰þýQ»6rsñö-¾ÿãÆ)òx[é2††8v ƒ+à†Y ’˜]üØ£BQ.¡¥²²àêŠ7Ш®^-mëXmÂö&2l{üX¶mTíÚLDÛÑh¤  í¶aƒ¬=/ `&Of5Ê`Ú·—m$–“ÃjÜJ 2§OÿÒŽ ÀðxJaáB` ™€…Ý37YõWîá6éÒ]ÐN÷Ï|qœ/)u‹Q¢rs`ll˜øx¶£QóÅÅ¡Q#tê„'tåÃŽâH$øùgÙ¾7rû÷ãíÛ¢•æ––pu…‹ úöEƪ”}cÆààAüñ~ýUé}-\__âøq¸¹)ì¶²S üÙ‰æõ¹©B“ …ððÀéÓ¨U W¯¢iS¶RÏ|>`õj¬[§È)'Ý cÚ4øù•vMÓ¦èßýûÃÉ©ÄU´:ÂÖññ¸zµŒm9eÁ¬] CCœ8Aƒyg‰q²ÆÕ8T¡‘ÄbŒ‰ÿEµj CëÖl¤R:ŸùŠ=™–”%/£FáÔ)p8(ò7ÈÂß}½z¡fM–âS3ññ°µ‡ƒŒŒ¯:°ü^^Ø´ FF8q*úþ$„ nåº' oÊ¡MÂ0˜4 {÷ÂÂ/V¾üVcé|æ#—žww\¹Rü«¦¦ ÕÁJ¥ùýw,^ŒjÕòÏ‘P†ÁìÙØ¼&& DŸ>JéE^\P „f˜=›6ÁÌ çÏ£{w¶£ae>R1ïÞaÀRÃ`æLlÝ SSÁÙY‰}Q „ðõÅÂ…Ð×DZc•Ýò@Pæ#_%'àÞ=Y"|ôì%\½ª»Ži7†ÁŒض ¦¦8sNNÊí./…yêϺOÀOcT³×sø‘NPëÖaÞ˜™!8={ª¤S!â·ñÓ_HWçØ1t˜hdhIùOµŽÁ˜1‹±~=¼¼ØŽ†}”ùÑ &N„¿?ªTÁùó…öÎV*Y Äþ§(13N*P¡À@  ¡Ë—ÃLJíhÔe>BtˆXŒ‰±?,-qþ¼ª‹OŠ)˜alÙXóß§OŸúõëW·nÝÀÀÀ’ZãÜ9¸»C ÀüùX»V‘wÖdºøwŽ¥§‡={0f ÒÓѯnÝRiï5;è÷ÙeÆ;cÞø{F‚—'…§]3/yf'E·>X«­Zµ***J$•Ò¢×®aèP˜:¾¾Š¼³†£ÌGˆnÑÓÃÞ½øá¤§ÃÕ·o«:€jöz=Ö™ ³°Ÿ`È5ä$„ŠÎ|ŸuÖ#ëÍ%!tf*22À¸qãJiùZwï‚ÇCN<=±u+mVUÍv¢‹ÄbŒ‹Ã‡Qµ*.^D‡ì„!-x²W HgTsÐsðÔ‰ˆÚµk3 óúõkCCÃ’Z¾ÊãÇprBR†Ç¡CÐÓöÿ¡Dc>Bt‘žöïÇÈ‘HKCß¾¸{—0Œ«qÚÌ1öˆ°è´ÌØ´7%F>/÷dïÌ'{øâ<­ýP.‹?~ü8uêTy’û²å«<{†>}”„Aƒ°?¥½/јÝ%bøpœ:++„„ ];6ƒ‘•@lå§¿Ôòˆ÷ïß7lØ0>>¾æç=Ý¿l©¼øx|û-Þ¼“‚ƒabòµ7ÔF”ùÑiò3ÚjÔÀ¥KhÕŠåx´ "==}ûöíáááÖÖÖÙÙÙ)))ëÖ­spp_ððáÃM›6íØ±£”–JJLD¯^ˆE8wŽv‘( e>Bt@ F „†¢eK¶Pl ÄLcËFêžÿ&Ožêµ-^pp0ÇëÔ©Sxx¸|x—––¶páÂ:xzz*±ïìl¸º"" âÚ5Ô­«Ä¾´e>BˆŒ@€!Cpæ ¬­ª^É@^2ót¿š–@dff6iÒäãÇ.\è«âCïòòÀã!$ àÚ54h ÒÞ5e>BH>>C† 8ÖÖ SÇã……ÙÌ‹òO°hÀµŸÀþ)¿ÿþûâÅ‹7nüâÅ •v,aØ0œ>Zµpå š5Siï‹2!¤Ü\ðx¸t õê!, Mš°PqŠ”@˜|Ãi6ÚÐa’‘avòŸ££ãƒ¦NºmÛ6Õõ*cäHüû/ªUCXZ·V]׎2!¤¨œðx E½z¸|³P ¤%6ó¥;ÊJ ¦™Z«t (ŸÏ766°yóæ3f¨¨W†Á¤IØ»¸xQÕ»k8u_"LQ=SSÂÙ pvÆ«WlTõû :i>à˜Y½ÞúÂæÉ^Áño3Ãçæ¤¿’¨,Œ?J¿¨¡Ê•sæ`ï^˜˜àôiJ{E™R SSÁÉ oÞÀÙqqlT*Ù)ANè›yÉ3;é¾*N055•~‘””T䥔””„„Åw¹|96n„‘N‚³³âï¯í(óBŠ'M~½záõk89•˜ü""TVɪ9èõXgú}hS ¾û| „2U¯^ÝÎÎ@@@@ÁöwïÞM:U:ªH¾¾øí7èëãða¸º*øæºžóBJ“qõ*llpù2lm ½š‘öíñü¹ÚS´¢…žÃ$%–@?~ÜÃÃa˜yóæM™2EOO/88800pçÎõë×WdOý…¹sÁåbï^Œ«È;ëÊ|„2dd _?ܼ‰&Mpùr¡:éÇñøySMŸ4-°áÚ7löƒ‘ž‘âû ^³fͽ{÷ôôôš6m:f̘éÓ§)´§;1y2lÞŒéÓygC™R6éî‘‘hÚaaùÉoØ0?Ž °f «ñ•JV±…/]öÂz D%9‚1c 㯿0gÛÑh6Ê|„r‘žá~ëš6Åå˨Séé°¶Ÿ[[¼z¥vžEÈJ 6ñ¥Ë^ Ì9M†±PQIAA2B!–.Åo¿±ÆÓ„9!D XZâüytìˆØX8;ãÝ;œ> >þû÷î±_Yd%§>—@d1Oö NôÌ Ÿ›“§ºˆÊ Ãðá ñë¯:›öÄb±“““¡¡á­[·ä7nÜ044ìÓ§DR±Ÿ ù! =ÃýÎØÙ¡A\¼(k_¼«V±Y¥Äˆcv>ÂËø›Öj°h×®¡ää`êTlݪî#keJLLlÓ¦©©iTTTÕªU“““Û¶m+ £££­­­+t+Ê|„Šùð½{#&ä¿?ììðô)«aUJækÉ“=üç‡b> †§@ܽ‹>}žŽÑ£áï®®ÏÒ…„„ôë×oðàÁÇçñxçÎ q®xE£žÂ#„h§”áõk¼z…‚›““1ljÖd/²J1²äÔu2h:ÒHß©O$q’¸á›‘¾1¬šéqØM411pqAj*<kkôêÅFpŠÆáÀ²‘^³Q†uzèç%3iÏ$IÑâ§þüŒ8IÕfzFV¥å?FŒó?d7jÀ5¨ø019..xòmÛ"$––•ÿ3h£3fïÞ½ÛÓÓS(úùùYZZvíÚµ¢÷¡1!¤’?ÆÑ£øç<{&kqtDt4«1)GÊcqÌ®B%mæWoUü’FÿÆév£ »¬ªà,ef&\\pëìíqå Tyæ‘&8räȨQ£~üñG???b±¸OŸ>ááá:uªÐ­(óB¾Vt´,¾z…ØX5=ÆýëeÆKžì-W „“tFŒî˜4ñ(÷Ê”ìl¸º"" âêUÔ«§¸ÀµAlllûöímmm###M>?ø|÷î]›6mÌÌ̤~å¿e>Bˆb0 "#ajŠÖ­ÙE™r“˜gøOö €ê-õì'=â`‹ QÃÕ‡ë!3ëŽúeߔχ‹Q§®^EãÆJ Ÿ”ù!¤„YÌ‹c%–@i›ÁOc˜Ôธ›Ö*uµ‹Hœ:kk\½ŠfÍTñÐm”ù!¤’¤%6ó¥;šÔà4ûÁÐÁÓè”KfîGÙ¯ÖZ]ô]˜•x. D‚ñãqàªUCh(U»V‰ŠŠ²³³355-çõ´¶“B*‰«‡jözÍÇUo­—ùŸ$#Nò!Rül¿@"„D »&+A’—ÂÔë]ÜŽh ƒ„¿?,,pî:tPeðÚäÇ]ºt111qttÔ+Çf7º¾ !„|%é)Oš;m3ýÆQO˜Å³òçÒ8À³‚W§ŠÛùfÎìÙccœ:….]T±ÖiÓ¦M‡f̘ѬY³íÛ· ‚Ò¯§ÙNBQ˜·Ea?åðÓ‹þ^Õ3æ ü׬Z‹Ã¬X##ÀÕU¥Qj£;wîtìØQúµÍÂ… 'NœhX®o”ù!D<Úο÷g#.þu“š^ …l˜µk±`ôõqô(† Qe˜ZÌÍÍíÌ™3òomll-Z4a„/óe>BùZâ<æÆ¢Ü—'KØÌû³ÚÝõûì1ÑÛ¹3f€ÃÁž=7N5ꂨ¨¨öíÛIj5kÖœ;wîìÙ³M lJ™B¾JÖ[Éå©9ÉJë&¨rÚóÁx.6hЭo¿Uvlr–––•;Öàk•½¥B¬Y³&ª¸e‹Œÿ(óBHå1¼8&à§2=˜sVá€S×zFÐ3âpôa`ÆyÑfäȦ’´;À à‹}O‰r5hÐÀÏÏÏÕÕ•2!„¨Âû÷ï·6nü[Np€lSÓ³½zÝmÕŠá¨âü£ôôt‰D¢‚Ž âóù999ªìñÑ£GOž<)ö%;;»eË–9’ËåRæ#„¥cæ;W×!!ÖÒïkÕÂû÷Ц 6mBl§->~üبQ£ììì"í;v\ºt©››çó‡ ªç#„¥Û¼ysÓk xR­þü¡¡hÑÑÑèÙãÆáöcÔx7n,’öZ¶lyôèÑ›7oòxßè|úôiˆÅH°u+–-CF,-±p!~þ%” ‘Ò%''7lØ033Sú­££ãÒ¥K¿ÿþûb×õИB”(77÷‡~˜Èç[)¤­;v Q#ÄÄÀË OŸbìXdd`Á´n‹Ù XC­[·NšöÚ·oêÔ©¨¨¨¡C‡–´œ•2!„(‘··÷11‹ôõ<>\Öúä ^¿ÆP»6üý†V­ðì\]ÁãáÍöBÖçë׋nÚ™˜oo8†A³fظýú±¿£1!„(Ã0&LøôéÓÓÌLôèþý ]‘•…&MŠ™Ø”N~^¾ŒÖ­ñü9ú÷‡×¯U¼Ö£ÌG!Š·iÓ¦óçÏ7´¶ž””‹½Âܽ{£cG¤¥óþž=q÷.Ö¯‡¥eþä'Ÿ¯ô¸ue>BQ°û÷ïÏŸ?ŸÃá»»s?~DçÎE|R;w"<­Z}}ÙÊÏÉ“‘—‡+ЪΞUjä:‚2!„(’´ŒÏçÿ—`¯cGܼ‰}ûðÍ7 B‹ðñA^žÂƒ×”ù!Da¤e &&&GvïÖÿßÿ`Ù²ÒÞй3.Ä‘#07/ãÖ\.ÆÃ³g˜=;ò38Xa¡ëÊ|„¢ïß¿÷ôôdÆ×××þÚ5Ù€oàÀ2ÞöûïpuEvv¹ª÷ªUÆ ˆŒDçÎxñƒÇC\œBâ×”ù!Däe nnn³~ük×e øä¶oGýúؽ»¼u耈šü¬4Ê|„¢Ò2†ZµjíÚµ‹ãç‡÷ïÑ©SÙ>©š5‘–†ðð ôWpòS ÀŠhÑAA• ^×Pæ#„¯%/cسgOM øúåðpwÇõë²m<+D:ùyëºtÁ«Wàñз/ž>­ð}t e>Bù*ò2†3fôïß;vÈ|ƒ•÷\.ºuCJ 6l@%NNo×N6ùY£BBàè//deUø>:ƒ2!„|yßþ‰ÜÜ øäzöÄœ9néYQNþä§XŒaoÿÊÜJPæ#„Ê“—1:tÈÈÈò'|åðÉMŠacSùh¬¬d“Ÿ]»"!ãÇ£OB© yÃîÝ»9Î×ø¤ôô°gΞELŒB¬Z6àÎt놷o1~X[#, mÛÒä'e>B©˜¢e rs±f ðu>©aÃк5Þ¼Qä ÒÉϧO1{67¢ysøûƒaÖ…F¡ÌG!S¨ŒAJ!>¹£GѤ ¼½p«‚䓟=zàÝ;ŒggB©€¢e (0à[²D1}ôè}}W¦ª½LŽŽ¸zU6ùyåŠlò3#Cñ©1Ê|„R^Eˤví’ øVL7uë"!ûö«œ_Ñò•ŸÞÞàrupò“2!„”K1e rsñûï°x±";³²Â³gðôÄë׊¼mA––ðõŃèÛ‰‰?NNxð@YÝ©Ê|„R.Eˤä>ww÷·r%vïÆÿýŸ‚o[„.\@@ê×ÇÕ«hß^^HOWn§l£ÌG!e“—1ìÝ»WVÆ¥ ø¤.Ä´i˜7Oñwþ‡'O°|¹lò³qãJî­!(óBHäe 3gÎìׯ_þ »w#1:(ì _A-Z`ëVØÚ"5Uñ7ÿ’™||ðà\]‘œŒ9sÐ¥ nÝRE×*G™BÊ0þ|iÃÿœ{ÌÍÅêÕ°x1䓟ŠÅçcèP4j„´4¥ÜÿKvv8hзo£kWŒ‡¤$õ®*”ù!¤4[¶l)TÆ %ð)ü Ÿœ‘22ÀçãæMeuQ,ùä§öM~Ræ#„_Æ€¾E‹”5à“Ú²qqî£J¦¦²ÉÏþý‘’‚9sЩ“ª°ÒPæ#„â_Æ %ð}÷rƒhÖ ÖÖxø¡¡Êí¨¤ÞÏžE@llp÷.ºwǸqøô‰…HŠ2!„¯ø2|¾ìXeø¤®_GëÖðô„H¤ô¾ŠÅã!&¦èä§XÌN0Š@™BŠQ|ƒÔ®]HH€££Ò|Rݺ¡]; €ìlUtW,éäçÇ0©©²ÉÏ7X‹çëPæ#„¢J,c@ß²eªðàppë¶n…¥¥*º+EÓ¦F@lmqïžlòóãG–£ª8Ê|„RTñe R»váÍ8:âûïUž¢£1t(NžT]§%‘O~ièä'e>B)¤Ä2°1à“»~'N`Ý:•vZÙäçÀHKÜ9èÐׯ³VyQæ#„|%–1HíÞÍ€OjÒ$,_ŽÿUu¿¥hÒgÎ ":ß~‹qãðáÛa•2!„È”VÆ€ÏÏ?x]Å>|fY[«ÝY²<?ΟülÞ6°¶ µ|(óBˆL‰e Ròß!lD>­Z!<œµŠ%ÍÊÁÍ-òóÚ5¶Ã*e>BJ/c@ß’%, øäìíai‰ÿþc-€R4nŒÀ@ Q#Ü¿ž=ÁãáͶÃ*e>B)µŒAjÏÙ€oèP•GWÀ¼yˆÇ˜1lÆP:Á×ff ‚½=|| °V!”ù!DVÆàÛà®;IDATèèXL>_v»>UªÀÒ!!XµŠÍ0Jgboo<}бc‘+к5.\`;¬|”ù!ºN^ÆpðàÁ¢e RÒ_ëÖ,ø¤>|€›–/dzgl‡RªzõàïØÛãÙ3ôë¯_³@™¢ãK+c ¨Ë€OÊÚ¿ü‚ßG:l‡R}úàþ}¬_sóüÉO>¿Œwåå)5(Ê|„ÝUFƒ”|À7l˜j£+ÙªUðö†……²3„bÀËK6ù™“ƒ+ЪÎ+í-×®áÄ åED™¢»6mÚtáÂ…ËP`À§¼ƒ×+çÖ-tè€_~a;Žr«[þþ¸t ˆÅ€àñ_üÅÉɘ1©©JŠ…2!DG•QÆ µg^¿FëÖððPmte13CTΞ…PÈv(Ñ»7¢£±~=,,‡â'?SRðþ=–.UR”ù!º¨ì2¨ñ€@‹ ÄãÇ00`;” ’N~>y’?ùÙ²%‚ƒ ]“”Û¶!"B!Pæ#„è¢2ʤöîÅë×hÕJžð4p qì˜òf•H:ùŠ-ðâ ‡¸8Ù«ÉÉ ‘`Âäæ*¼sÊ|„uwùòe‡³lÙ²"íÓ¦Mãp8Ož<©è Ë.c `õjX¼\uýU9y2†ÇæÍlÇQYÎΈŠÊŸülÑ>>ÈË“e>±±X»Váݪë“B>srrjÞ¼ùž={ÄËÉÉ9tèзß~koo_¡»•]Æ %ð©Û¾‚ÆŒAãÆhܘí8¾BÁ•Ÿyy²ÉÏ‚ŸfV¯FT”bû¤ÌGÑS¦LIHH8W`)ü‘#G222&Ož\¡û”«Œ2ààä„gÏðÃlÇñÕêÔ¿?Ѥ ^¾Ä½{ù/‰D˜9‰{SãŸ(!„|6~üx???y‹ŸŸ_µjÕ†Uð ÜÆË(cÚ·O|rþþ).þ‰À@üóÛ¡|¼<,^ŒŽ‹/ò[°@Ç>¨ý•BS§N‰D{öì°cÇšê,Wƒ”tÀײ%†ÿºU‚ÃÁªUغUM –ÓåËptÄï¿—x¤mV¦OWTo”ù!š¡sçÎmÚ´ÙµkWNNÎzôèáààPþ·—«Œš6à“<Ó¦ÁÀoß²JÅ¥¤ÀÓ½{ãùó2® ‘# éS_!w!„˜:uêÔ©S§M›–ššZ¡_¹Ê¤üýe¾#¾6\Uzúß}33ܽËv($‘`ÎŒÔT$'ãÓ'|ú„äd$'#)IÖ"/XôòBß¾¨^ý+û¤ÌGÑ£Gþõ×_ýýý­¬¬<ʽöD^ưvíÚÒÊ ™>)[[dd@$»wšq†ƒÜ7ßà›oʸF$’åÂÔT…lÒ­Q?ZBˆn3773f €ò¯m‘—1ðx¼™3g–qµ¿?âãao¯Oø 26Fh(ž>Õ°´WNúú°¶†ƒºwGݺ_?Ê|„Mbhh`Ê”)å¼^^ưk×®ÒÊP`À·d ôô¾6PÕkÞ vîÄ­[l‡¢î(óB4FFFÆÞ½{{öìùåÚ–?~y}yˤöïG|<š7×°'|ýõ~ú >>lÇ¡î(óB4@ttôþýû‡ ’žž¾ô‹Ãk†™8qb‘Æ ”1°r% ±>©D÷î?ží8Ôe>Bˆ8pàÀ¸qãž>}ºa×"¯¾{÷.88øìÙ³Ë[Æ %ð©À°U­zu„‡cÄØà”|‰2!DüùçŸ Ã$$$Ìž=ûËWŸ>} `ùòå ÃH[*PÆmðÉmÙ[[Tü ÝA™¢ñ¤™ïöíÛ'Nœ@…ʤ´cÀ'÷ø1pèÛq¨/Ê|„'?¢oáÂ… e (0à[¼X|,À™3øí7¶ãP_”ù!ïÙ³gÒ/bccÇ_Þ2©;;Œ¥Ü(U¦A ˆ¬,\¼Èv(jŠöp!„h¼‚Dz=zÀÊ•+¿)sgBaþ9|Ú1à“JKCÓ¦ÈÊB\jÕb;µC™¢Ù233ß½{'ÿVºÈå§Ÿ~òòòjÞ¼¹½½}óæÍííí[¶lYôÍû÷ãÕ+ØÙiÃá®U­Šž=eÛ}Qæûe>Bˆf{úô©|IgA999÷îÝ»wïww÷ÕÒ±]A"‘vø¤€‰ ÛA¨)Ê|„Í&]ØY''§5kÖtéÒ¥˜×´uÀ'eb‚¤$lØ++ÌËv4ê…2!D³=)¡p­gÏž¾¾¾]»v-þmòߢEZ8à“Š‰ÁªU¨^Ó¦Ñø¯ ZÛIÑlò…r7>tèPXXX‰iÀþýxùvv=Z¹ñ±¨gO,X€  J{EИ¢Ù ÎvÖªUkéÒ¥?ýô“AiïÑ…ŸÔš5‘”þÿD—И¢ÁD"Ñ‹/XZZ®ZµêŋӧO/#í8p@û|r7¢~}<Èvj„2!Dƒ½zõJOOï—_~yùòåâÅ‹ÍÌÌÊ~H$;‡oáB-ðIÕ¨Œ \»Ævj„f; !ÌÌÌìùóçõêÕ«À{¤¾fÍ0fŒÒâR'°µE)à[¸|…,[†}û°n]¡ÆíÛ±oK©ÍvB´×‘#²ŸŽ/éüÒ¢E¨]³få·Ü¿ŸFŸ>ìŤ:”ù!ZŠ|¥h×íÚ@j*¬¬šŠ¡C‘› }H 4ÛIÑ|ii8{¶hã‘#ˆEÆ4à+^v6ÜÝÑ´)ÒÓáá—/èÈGÊ|„Í'‘à‡—ßB¾2™™!%yy˜3—.Éuãÿ•N l !Ú/- ãÆ!,L6_wô¨lÀ7aË©‰¬,üú+^¼€ÌÍÀÄuê ^=øûç_F™B4‡ááX²¾¾‰°b@¾ÌÍáë‹I“pâDi—éÆÿ.ší$„h‘?þÀ‰j2à‹ŒŒ\·n]NNNé—………­+R] $––ø÷_üï¥-c¡.„¢a?ý$Û”rÁvG0:u:tèPÆ ÿüóÏììì//¸téRÏž=ûôéãä䤢˜8Ì‹›7ak[üº1æÓ‰ôNÑ!))HI¥%^¼À‚…^êÖ ƒ«,‡³|ùòÁƒÿúë¯üñǼyól?ç›óçϯ\¹òúõëÜÝÝÛI T¦}{ܾѣqáBÑ—t#óqÞ´”¢%ÒÒÊØˆ’ÃÁ¯¿bõjÏæ1 Ó±cÇ»wïJ¿µ°°ÈÌÌ´²²JMMýçîÝ»mÛ¶UeT2b1V®ÄÊ•Hò½½áëËB0ªE³„mW½:±v­2Òž¾¾>ç õêÕ“¾*öÉ/ÎÌÌ O{ÜÝÝÙI{ôôàッeK=¥tcÌG³„­Ö·/@ÍšJº}pp°¤À˜éöíÛË–-³-ðÍÍÍ­}ûöòa_AgÙ²eJ ¬¼FŽD«V:Ïžº²Â…f; !š/=U«mär±t)–.UÙi´ñññ;wÖ×׌Œ¬[·®¼ýìÙ³üòúaÆ;vL5±•!#“&áøq¬^E‹ØŽFé(óB4ß—™¯V-:gg•…‘‘Ñ­[·øøøk×®µiӦȫ]ºt‰ŒŒ,ØÂår=hР//ørاF¾‚rsabÂvJG+\!ÚeÎ\½ªÊ´`úôé/^\¿~}±i@ÿþýÛ·o/ÿ–Ãá,RÏIEH{ ÌGÑÒÝ˪VÅñãøë/ª²ó?þøÃÏÏÏËËkæÌ™%]ÃápV®\)ÿvèС¬-é$4ÛIÑpqÁÑ£hØPÅ=?~ÜÃÃÇãB©¤;wîtìØñËöºuë&$$û–nݺùùù©×’NÝC™BT'>>ÞFµ«oÈ—(óBÑ-´¶“Bˆn¡ÌG!D·ü?>U/ÑË",/IEND®B`‚opengv/doc/addons/images/multi_viewpoint.png0000664016516101651610000012022513344612246020237 0ustar dimadima‰PNG  IHDRœÍ<<=bKGDÿÿÿ ½§“ IDATxœìÝwTgÛðkva)Ò{QP@é *jì=¢¢±E,€šX?15ö%ö®Øõb‰=DQQE,ô^vw¾?Ö—×*ʲ³»Ü¿“s²ÌÎÎ\œ#Ü<3s?ò,!ÿvóæÍÛ·o²,«®®nee5`À}}}®sBȧ0TÔ ùÀÎ;“““?ØÈãñFmccÃI$B© ×Q,ׯ_ONNfæƒí‰dÿþýœD"„*¢¢Nȿܾ}@Å+X Ã…Âèèh.BBH•PQ'ä_Š‹‹+Ý.-ó òC!_€Š:!ÿòé§L„B¡Ü’BÈ—¢¢NÈ¿ðxŸú¡066–[BùRTÔ ùŸ¥K—~b¤Î0Ô-BQhTÔ AQQѵk×tíÚuß¾}|>¿ÒÝ„B¡»»;è"@÷I-µtéÒY³fùùùíܹ3//OGGçÓÈ•“H$»ví>|¸††Æøñã‡Þ©S§šNK!UA—ßIí’››+½r>hÐ SSS777zzzU¬èx<ÞØ±c555;¶cÇŽ!C†Ô`bB©2©“Z$??ßÑÑ1###&&ÆÉÉ©¤¤DSS󫯲ìºuëêׯ߿ÿ[·nhÓ¦ìÂBÈ£{ê¤Vøë¯¿ÜÝÝúô铘˜(ÝXŠ€a˜)S¦ÈÉÉ:thJJÊ… :wî,ƒ¸„òUh¤NTßÊ•+g̘ѯ_¿“'OVst^)‘H´dÉ’Ë—/_¹rÀƒš4i"ÛSBHUPQ'*+==ýôéÓ~~~oß¾õòòš1cF@@@Ååפ"""Þ_nÕÀÀÀÐÐ0##£¸¸X"‘hhh˜˜˜8::êéé}ìt‰„Çã-[¶lΜ9+W®œ:uªì¿%Bù$ºüNTSqqqãÆSSS]\\Zµj•˜˜ø±)e¤<<Ü.öùóçÒ/utt¼¼¼ôôôtuu---Ÿ={Ʋ,˲éééöööîèҥ˰aÃ<==3227n,‰Z·ný‰ý !D†¨¥¨”µk׎9ò矰hÑ¢Ó§O;88Tó˜æææÒ×ÅÅÅoß¾ýôþÒ3þõ×_/^¼8sæL5ÏN!UGE¨‚W¯^­\¹€ŸŸ_“&M|}}%ɧ¯·}}ýò×™™™UùÈøñãO:µsçN·|ùòmÛ¶É* !„| ÝS'J¯´´´eË–¯_¿vuuíÕ«×ýû÷e~ --­ò×………UüTŸ>}öñáÇK_„„„¬\¹rúôé5•R›Ñ=u¢ºtAL ª0¢Í°·gk¾@–•••¿.ïR+,,”®ä–““S•ƒ°,Û½{wkkë¡C‡(ŸØŽBd…Š:QT¦¦8zgÏÂÚú£ûÔ©crñ"O]½¦³•¿600¾Íš5svv®âA†™8qâÓ§OëÖ­{ýúuggçüQöY !µu¢ØzöDD„¤OŸÊßýí74h ‡Ò ÃXZZJ_«««Eºt Ÿ’’¢¥¥edd@"‘È.)!¤V£{êDá=žoRq{Û¶˜6MçÏÈÈÈÎΖ¾¶µµÕÖÖ®þ1‡ æååU·n]‰DÒ£GùóçÓôs„j¢¢NWâß6NN6Ò´´ÌŠ‹ÿ÷žŽ‚ƒ!»NôÞ¼yS[[›eÙ””éFSSÓÆËêõë×p÷îÝëׯGGGÿôÓO›€–BªˆŠ:QH99˜7¯Áúõj,[ª©)X¶Ìl̼¿˜Ê¢E¨_¿æÎ¯®®.‹_½zUVV¦¦¦flllccS¿~}™Oøêééy÷îÝŒŒ 33³³gÏ^½zuáÂ…4d'„|*êD±ççß1¢Ý•+‚‚>w­qã&ÇŽ ¤S½ (-€îÝ1yrÆÐÒÒòöö®ÑS”swwPZZøòåËF7N>§&„¨zPŽ(’Ó§ÅÎÎß„„ Äݺ1t¸ß |òvéH]O[¶ †—H‘ÿÃkàðáãF3fŒH$Ú¶mÛ—ÎrC!TÔ‰Bxpð`Œ¹9úöÕyõê•ÁÅ‹ùçÏãƒn1]]X²¶¶5çýÙfä¦M›6{öì‘Îïïï?lØ0ùg „(5ºüN¸––†9sœ·mã³l‘¶¶öXûùYWÚz®«‹N0q¢Ü#V.++ëÍ›7ž}jggG‹·Bª‚Š:áLInî­!C¼®_×(.æ©«_oÑ¢ùáèW¶ÆæÍ5tá]"‘äçç—)‰òòòttt>±»‘‘‘´Ñ\æºv횘˜¨¡¡‘––Ö¦M›&Mš;vìý•â!¤RtùpäèQ‰«k§óç5Š‹Ë¾ý–‰õ «ó‰Š`Å ØØÔPœ¨¨¨ˆˆˆò/‹‹‹/]ºZC§û,éð ,˲,«§§GsÔB>‹áäÞ!©Í"¶oçÿßÿ5ËÉðÆÔ4}æÌÆ?ýÄu(Åõöí[±Xlmmý믿>zôhóæÍ¦¦¦\‡"„((*êDŽÞ¾ÅŒlp0òuêèl܈#ðñëÛ¤\NN޽½}NNεk×ÚµkÇuBˆ‚¢ß§D ÒÓ/·o_jcƒ}û ®Ú¹³Úóç5Š*zDFFnÞ¼¹]»v¯_¿þá‡òòò¸EQ84R'5Œe±o_éÿýŸ - €°_?U«PÞzN¾œÏ_ý5nܸmÛ¶q…¢XhœDjPØï¿?ÐÑÁ÷ß ÒÒR­¬â7mÒ8y’*z5-[¶ÌÇÇgñâÅNžŸÿöíÛÜÜÜ‚‚ p± !DAPQ'Õ%NH@ß¾çÍs 3uuqäˆyB‚Ý!\çªE¬­­###ÏŸ?o``âééÇu(B¨¨“¯—ñôé%WW8;ãôiVW÷Žþ«W<¸¦×E%ijjºººXºté½{÷.]ºÄu"B¨¨“¯!.-ÅÚµFžž]>„D’ÿÝwL||ËãÇÕ¤«£îœ?~ùòå?þøcYYÙ„ ’’’¸ND‘zPŽ|±ë3gZ­^íPV ÝÅE¸tiÝ~ý¸E>´|ùò™3gº»»GGGÓÊ­„ÔÔÒF¾€ðÞ=  ïK—¤ëé™›öíËu(R¹±cÇÞ»w/00a˜ëׯ7lØÐÒÒ’ëP„šE#uR%éF÷íÛ1)IeY=½û4Ù²…§¡Áu.òy©©©nnn,ˆ‡‡ÛÛÛs‡Rƒh¤N>£$7Wsóf“e˺ä䈀ì‘# ÿø£M&£<$‰‡‡;;;¡PXTTdhhÈu(BH ‘:ù”k?üPoË;‘@F«VâåËÍ;tà:ùb,ËèêêþòË/ûöí îØ±#ס!²G#uR¹üÐPÝß~ëpù2€ƒºGštéÂu(ò•†ÑÕÕ‰Dááá©©©4›,!ªŠZÚȇÒ<¸R·nöíqù2kj1~¼uZ¨¢+?55µË—/ߺu«eË–ÉÉÉ-Z´¸yó&ס!²D—ß9“››»eË–ÐÐPss󬬬իW»¸¸p)5UÓ&¬Z…‚!7fŒéᅢ¢iÓ¦­Y³ÆÇÇçøñã\g!„È un„„„øûû=zþüù………ÆÆÆ&&&/^¼àóùbÙkãÆ9ìÞm-‘ÈêÜ‹µjÅA"b±xýúõ#FŒ011ùí·ßºtéÒ®];®CBª‹Š:6oÞ €«Š.‘H^8€V­¼öì±”Hž˜™áömý“'u©¢@SSsÆ ±±±úúú'Nœ°··ßºu+ס!_†Fêò# cbb¸¹¹ÉÿìÙ÷îÅuîÜ.'lmýýþò -|N> §§àêÕ«EEEB¡ë8„/C#uùIKK“¾055•çy_=z$š4ɰM›v99 óêÇñðaÃY³¨¢“Y³fÍåË—'MšTZZÚ±cÇ}ûöqˆR%TÔå§|nÎŒŒŒÞÊÊÊJII‘ý)ÅâðaÃ4]]Õ6n„HT0l?!ÁzÝ:¨Ä,¡b±¸cÇŽàÎ;åoݺ%:wî,‘H8̦¾ùæwèСk׮͟?¿¸¸˜ëD„Ï£§ßåÊÉÉéñãÇÝ»w?wî\ùÆ×¯_O:uãÆ2ì‰DI›65ܼH´°hxú4š7—ÕñÄ›7oš6mª­­e``™™Ù¬Y³²²²û÷ï›››sNEìØ±ÃÑѱ]»výõŸÏïׯ׉!Ç9:vìÃ0~þùç„„„§OŸ®_¿¾[·nÉÉÉ2}:×Y!ÿB¿þ”žP(ŒY²nn­2âllؘ­­[kIEðäÉ“¸¸8Ïž=ËÍÍå:Žê³³³ÓÕÕíÔ©€·oßr‡ò?TÔ•[ÉÝ»‘FFgÏÆãÇpuÍ}}}aaaB¡0++‹ny¢ 螺 #FŒp8vÌ€@P:ioæL533®cqàСCß}÷ݸqã¶mÛ@,wîÜ9,,,44´eË–\§«"##íìì ýýýÍÍÍçΫ®®Îu(Bj/*êÊD(Æ/\Øäða|˜ë,„Ôt WInÜH23kµq#RRкuÙµkMcb¨¢‚X,>räHYY×AÈ¿tìØ@^^×Y©¨¨+–°²»våuèà^RòV xºt)ÂÂÞÞ\çRt|>?::ÚÑÑqÛ¶m¥¥¥\Ç!0hРøøøÀÀÀÒÒÒöíÛ6Œæû#¤¦Ñåw…‘Ÿÿpøð§NiÐÒÿü3ÄÓÑá:–ÒÈÊÊjРA^^ž­­íÌ™3ýüü444¸E <<¼k×®ÖÖÖ‘‘‘ÚÚÚ\Ç!D•ÑH{YééW‡ ƒ““Ë©Sš@œ‡‡èáCþÂ…TÑ¿ˆ‘‘Ñ?þàÅ‹&LpppøóÏ?KJJ¸ÎEЪU«¸¸¸ãÇkkkïÝ»w„ ………\‡"D5ÑHc’þ‰ïÕËEZ{Úµ“üþ;¯U+®C)«òÁzù++«3føûû—ÏNC8TRRbgg÷æÍ›C‡ ©}S"4RçÆ¾}û-^œÑ¦ ï›o\JJÞhj>_±ׯSE¯##£Ÿ~úéý-¯_¿ž:uj½zõ~ûí·œœ®‚)MMÍ7nÌŸ?È!ùùù³fÍ*((à:!*…Fêˆ>wn{¯^ XÖ  ½{?úö[qÍ%KJJŠ‹‹kú, …EÒYð䢨¨hùòåB¡°â[fffÓ§OŸ4iÝÖU'NÜ´iÓÀ;ÆuBTu9JH€P˜gk»×Ææ‡ÜÜb@ øàdr­öðôô¼páM Ϲ˜˜˜ñãÇïØ±ÃÍÍ-44ÔÓÓ“l$¤ú¨¨×0–EZÌÍqà†G¿~£ôõîÛ÷;Ðñ¿»¤khìiÞü޵uMgÑÔÔ”ÿ­e yŽŒKJJ6oÞ\éHÝÖÖvÖ¬Y£GrËC>ëñãÇÍš5³·· ÓÕÕå:!ÊMë*->ݺÁÈ÷ïã›o ¯ÿ,'g_Hˆººz§²²"MM­’’{ ã!N µm«¶mœ¹­ÜfÍšU±¢;::.\¸pàÀ´Äˆ*,,¬[·nóæÍuuu 544ÔÔè÷!_‰~ÇÉZq1¾ÿA$‚òòðö-rr`añ"2Ò#:@—.]¤˜«©ÉîÞ-Ò×W»ySìæ†™3A]X_+;;{ãÆïo±µµÝ²eKLLÌàÁƒ©¢+&û÷ï¯[·À„ Ú·oÿäÉ®C¢¬èלŒìß™ --ܹƒÄD„‡C ÀÝ»xýb±xø÷ßçææöëׯE‹²ÌÍ oÞ\8dÈŽiÓ‚†'‘`ùrÖÍ .pýý(¥5kÖ”ÏY&-ç þþþt½]ÁikkëééeffþóÏ?111‰„ëD„(+*êÕœŒuëûöáÄ œ96 &mÛ@ÆÒ5R/^|óæMKKË;vH?aj ໦M555æÍ³¿y³øÌ891OŸ¢{÷’~ýšÊÍ÷¥œrss¥£=[[ÛÍ›7S9W:ÆÆÆ111ÿùÏ5jÛ§OŸ—/_rŠeÃ’/ËÆÇ³,Ëúû³;>˲lH»v-›’Ré'nÞ¼©¦¦Æ0ÌùóçY–3g€#F°ÀKGÇk×®•ïù4>þ7-­†aÖÀ@¼z5+Éá{R ,°¶¶Þ´i“P(ä: ©®®]»˜2e ×AQ24R¯‰ii°v-Üݱb „þýáá}ûbòdTö{^^Þˆ#D"Ñ”)SºuëV¾]:Rç?~|äÈ‘òvŽŽÏžEîÞnÝ“Ãûé§DDÔè7§$I½zõit®öîÝëïï¿hÑ"kÖ¬IOOç:!ÊŠz„‡ÃÊ Ã†@—.02‚žtíŠ'Чϧ?=iÒ¤¤¤¤¦M›.[¶ìýí¹bMMKà›fÍÞßnaaá5jΟ_Ú¬Y “€6m0e òóeûm©7zôhš VeXXXlÙ²EGGçÈ‘#Ó¦Móòò‰D\‡"D PQÿˆ¬, ŠæÍ Q#deáÙ3”–ÂÕ©©øã*æÀÁÁÁÚÚÚû÷ïÿ`n –aøÎÎ|\\*ýì”ÐÐóæ‰'M‚D‚uëŠllØ÷Æô„Ô­[·îÕ«×ìÙ³ÕÔÔi]vB>Šú{XÛ¶aÀ””ÀÀÿüƒ{÷CCÄÆâéSH¯ëV¹‰öùóç'N°råJ—J+·³3€åË+]´J[[{êo¿ñÿüóúï¿GÚ99Ì!èÛ/^|íwHˆ’±±±9sæÌèÑ£‹ŠŠúõë׸qãGqŠÅEExò+WâÍ0 ¶lÁ‰¸r<vïÆãÇprGG0ÌU,1BÚÃ&-í•pvpòd\\Ü'å=mÚÓàà¸ñã¡«‹Ó§Ë6,›=¥¥_”‡¥–——gii©££Ó A•NH©ÅE=2ÏŸ@PfÌÀ‰0}:6m‚§'ôì‰F¾úð{Ø*áâ _Ʀ¦¦Ÿ>ÚáÃ]·n=xðw:êeeêK–ÀÓaa_åbaaqéҥ˗/kjjnß¾ÝÍÍíúõë\‡"DáÔ²¢.!#æÎE‹ؼ† ÁàÁïFäC‡"0Ÿ+±Ÿ¶páB†aöìÙcbbòÑýœ4‰¤ƒÏR³±1½zuc°µEL Û¶mþ€ï¾#BTÇ377gYöÀOž<É ù„TP›Šúùó°°À?@çÎ03ƒôai__9‚Ndužò¶©S§JÛm?ÊÁUWgŸ?ß¾n]Þ¢E‹‰ÿ‡ovéRèž8GGlÝ Z˜‡Ô Ã\¸páØ±c>>>yyyÝ»w¿sçסQª^Ô_¾„:wGGdfâñc°,¼½ñú5æÍ«‰s–÷°-]ºô3»ª« ëÖeXöï5k¾ìÚÚöûöÍéÑ#ÇÙYYÈmÖ ~ufB”ˆššÚÀ¬\¹òÂ… Ó¦McéZB¨fQ/+ßÂ×, ccœ;‡«W‘žŽúõñèîÝÀaÀç×ÄÉ÷ïßÿ±¶J©7n `â—_'°°°Xþ÷ßqqùþ™É0úÑÑl“&´ ©UfÏž=}úôíÛ·3 sàÀO?pJHm BE=.K– ?jjX¹GâÎhkãàA<}úî6¹ôÆyIJJš4i>ÑÃVßÝ@g+«¯<%Ãhúûœ=ûŸºu±Ë—çÙØ°çÎ}åÑQ*ššš+W®tvv~ôèÑØ±c[´hñ‚>Ií¦äE]"Á­[xû&LÀìÙ8w ƒ9s°c Ô¯/‡,b±xäÈ‘Ÿéa«ÈÙ@ôÁƒ·nÝúºóª««ÿ°pa§—/ñÏ?iÆÆzééLÏžèÛ))_w@B”޵µõðáÇnkk›•••””Äu"B¸¡œE½´YYðÃðòBp0Œ#`cãÆaÌÈ3T•zØ*rv xúôêÕ«ÕMСCئM+ŒŒ$NŸ99 W¬€X\Ýâðôôô¶oß¾uëV“'OnҤɩS§¸E”°¨> 3³wϸuî këwS¼ùûcß>´jÅI¨ªö°UäèÈ2Œ#Ÿß­cÇêÇøvðàŸÓÒx–tè VX¨$òðÀÝ»Õ?2!ŠÇã•–– …B‰Dâìì š£†Ô>JRÔããÑ»7{{äæ">¾ý/_bêTnÓ}A[EÚÚLýú<±¸¹Œ®+ðù|ØÛ¿Ü¶m†“S¦––ZL ¼¼rGMšMj@pôèÑû÷ï;88DGG7hÐà­˜@j.ê……Xµ ~~`hˆsçpö,Š‹Ñ¼9âãqñ"ðù_:{kMø‚¶Ê°NNV'ÃH 6\§‘€É“%b±þž=Åõëcï^ž‚…åàà`çÎoÞ¼¡‰çH­¢x4 IDATE=* B$‚º:.ÄîÝxö ææ8| ÐÒü{N1”÷°8p *=l1®®rÂÂRdúhÇÓ©[WòÇó{÷Žäñ´²³ñý÷…:½›—U·fÍš;w._¾À„ Ο?Ïu"Bjœbu±W¯"'†Çܹ¸q,@p0ÌÌ`Ð X[s³¢÷{ؤ÷𾆳3€±^^zÒeÚeŠÇãÍ?uÊ2) kÖHêÔ©sõj©ƒ;o­CTÃ0~~~uêÔ9sæÌæÍ›‡šÍu(Bj§E½¸¹¹0t(:uz·¤ÊèÑ3ÒgÍ&OÆðáÐÑá2äljD¢¯éa«ÈÙ@ýââš(êRV66˜2åÔÊ•ÕÔb1³`ÄÕUréR Ž…Ò«W¯M›6mÙ²ÅÐÐ022òÚµk\'"¤¦pWÔ7o†©)¤Ó£vîŒúõßÍ^>cv쀻;gÁªì+{Ø*rvP»îK'‹ýBý'Lhõøqþ¨_Ÿ÷ä ÓµkN¿~´ Qy Ãúúú~÷Ýw:u¢†7¢ªä[Ô##ѵ+üýÀÖ……ïb7IISaaa‹-úš¶Š „FF‘(¼æÓµ³³Óý7Ö–§NÁѱlÃZ†ÔšššcÇŽmÕªU=$ITT׉‘±ªu–Å™3_y†ìl,]Š~--\º„H$èÜOŸâàAïÍ•GµzØ*#}VnþСÕ?TUÕ­;.%%nÏxy!+Ký‡Ò]\h=¢òø|~PPÐÍ›7ÕÕÕ7lØÐ¢E‹¯ëX!DaU¡¨K$?W®|ÁQYááþ´0 æÍÃæÍHO‡‹ öïGl,x<°³ûÊÔ\«f[E‚&M8Èñá5mmíf£F!4tÏ7ßd¦ññhÚS¦ °PnáÇ““Ã0Œt𣆍ŒÏu‰“&ýoõO++Ã… ()ˢ̚…ØX`áBœ<ùnÒÖaÃÞ­­¢´ªßÃV ggç׬‰•Í«ˆaF]ºtsçNј1‰°n]v½z“'åš.Ì™3'>>¾ÿþ¹¹¹...‹/‰D\‡"¤º>YÔÅbŒ‹Í›O®oVP€‚èÞÝ»ãÒ%ðx;ÐÒ€  ôî uuææJyÛï¿ÿþõ=l9;Ð{õJþ7ù†éïç§¶cÇ£M›†ÙÙß~‹¾}ñò¥œ“"gÒ9jN:•””túôiFf²"¤š>^ÔKJðí·Ø½ûÝ—®®•ï¶lLM±gtMQV‹cÓ&88È4-ÇÞïa›0a‚,íâ E:Ý»w—åa¿„s@@îµkG‚¦&NŸ.²·Ï[¸Öƒ!*oĈçÎÛ½{7ŸÏ_»víŸþÉÒs£Di}¤¨ …:§O¿ûÒÄÆÆÿ{÷Ú5tè€_~[[”•!!‚‚…j41‡dÖÃV‘¹9ŒŒÔ Í%ùK´ñövÙ³„ééi—•éÍ OOܹÃa$Bä [·nŽŽŽ)))AAA“'O¾}û6׉ùJ•õü|të†÷o¬º¸àí[üöÛ»B®¦†ë×!mô0©©X»V.i¹$˶ʔÚÛøåÛoe~ä/foo÷øñnÖÚQQlëÖoû÷§õ`ˆÊ«[·nppðŒ3Ú´i“™™yPÚ›CˆR©PÔ Ð¯>XÁÉ ¥¥X°ë×£¸mÚàäIܺššÿÄ«¨ÜÜ\Ùö°UÄwsPQª¸ZXXŒ>~œ‰‹‹ëÜY²!!pr¢õ`ˆÊ4hвeËLš4iذa .ä:!_æßE='ݺáêÕ÷ºw&&øýwœ= <úõƒ®®¼BrOæ=lI‹ú¯òùü:ÅÓ×o²aôèì† ñæ ¾ÿ>¥IöÙ3®cRãzõêegg÷ý÷ßHLLä:!Uõ^QÏÌD—.ïÆßˆˆÀ€˜8ÞÞPœ’#/û÷ïß¿¿Œ{Ø*rv`š‘¡@EÐÖÖž¼k—a|¼pݺ|†©#qvÆo¿úz‰J5jTBB‚Í;w\\\ÆGOÏ¥ðߢž–†NùÑ/\ÀàÁµpi¯šêa«ÈÅ@fhèÆkð,_‡ÇÓøñÇ+7^³±á—–bþü¬ºu…gÏr‹$ýó:%%E[[ÛÀÀ€a15ƒ…÷ߢ~å œœàæà£ûž>¡CQ›æg(ïaëß¿¿Œ{Ø*²±ih—•Å*êRý;¼xÓ§s 22½{cÔ(¤§s‹äãã»xñb–e}||s¥kK¢þ[ԇő#ˆEQ‚+0v,¼¼`dô¿Ýÿú #FÔžÞåò¶íÛ·×øÉ†ut°|ôè?WuôîpâÄvkk¨«cß¾2;»Œ9sÀi'!5ÊÆÆFCC#..îâÅ‹Ç/))á:!Ua%>pp@ß¾ÿÛ˜žŽGÇñð!æÏÇüùPõÙ—¤=l<¯†zØ*RoÜ11z¯^Éá\Õáéíí™’‚„„Òqã7n˜,ZT|îœÖîÝ¡ˆåçæævïÞ½””ssó+W®œœ³¶ÊðÝÜ”ªèϿՈj±±‡…@€}ûò­­ŸO›‰,û®À‹Å w¢”´´°|yùWº^^]ž>ÅÙ³¥ÆÆFññðð(Û°Ãt¤6¨íE}ñâÅwïÞå°‡­"‰“€¥£F©À³r•jàââxð bcèŠDõ׬A‡ Cù÷{÷.víâ4#!_kÈxy½{íà={¾>{ö†±±ŽD¢þÃÂ.] Ÿ<á0 QmÊTÔ¯^½Ê0Ìܹs?Ø>a†a=zô¥¼víÚÂ… ¹ía«ˆçê À•ÇKIIá:KMjذQRÒ…þýY}}„†Š:tø×»3füëÊŸ?thæ¥K::ÆbqýiÓ0j”$7—ØD%)SQ’’rîܹò-‡ÊËËó÷÷ÿÒC)J[EÎÎ`<~œ“™Éu”šÇ²8uª~dd%í>ÁÁ¸rEþ‰‘U«PÙ0̯̣qFÆ›  hh`ß¾·¦¦‰Û¶É?QaJVÔ¿ÿþ{--­mïýlÛ¶ÍÈÈhРA_têa«HO¯ØÐ%%‹Çç:J {ô:áûï‘‘QÉ»,‹‰iñ+¢”QáF¡”@CÃrÙ2DF&êêZ••5 À”)ôïœÈŠ’uCCÃ!C†œ9sæÍ›7µÛãÇù³gË+!2Õ­Û§ÞuuµJN¾Ù¥ x<¬[÷ÆÊêÅ_É+QeJVÔŠD¢]»vغu+€/ºöþ~[àǦuäš~›6~õñá:HÍH°kž=ƒ·7ÜÜ`nÞGÿj¬^ͪÒ<<„üWƒ¶/"44ÇÌÌ2+Ëzà@vÞ\WWwïÞ½†††ƒ®â§²³³GŽ©ˆ=l9;pa˜Üœ®£pO øùùuìØÑËË«¤¤äÈ‘#,M£MTO÷îYׯ_µ¶ÖbY‹eËØ=²bc¹ÎD”Ru#Fø¢Gä^¾|©ˆ=l™™ÁÄD—e¶iÃuîikk/[¶ìâÅ‹ Ã,^¼xÈ!\‡"DöL:¦¤ïÙ##æÂ~“&1AA\‡"JF)‹:@ ê¿Üƒƒƒ=ª =l•rrðôôi®s( >ŸÀÝÝÝÒÒÒÏÏ@hhh­ÓJTŽÖ¨Q’ØØ{ú,ÛxÅ øú"+‹ëPDi(eQÏËËÛ½{···wÅGä*½0›˜˜(]¬Ea{Ø*ʯWÀú;ýß|}}Ÿ={Ö¦M›7oÞôîÝÛÕÕ5==ëP„ÈÏÊÊãõë³f¡N=šjiy[ñ¯/Å dEýþýûûöíóññÉÍÍ•>nö¾ÔÔÔ#GŽ|°Q)zØ*ÒñôÐD Ò¬ÿ&½á’ݰaÃfÍš™ššfgg?}ú”ë\„ÈÃØ.^ŒˆˆW––楥­fÏF@ ¹ŽE’õàààQ£FÅÇǯ]»¶K—.¼?gΜ7“ö°YYY)r[EÒ®¶..Êq³@î\\\îܹ³{÷n³gÏvww?pàס‘5''ËçÏÃúõƒº:¶nÍhÐàî¦M\g" MÉŠúï¿ÿβlJJÊäÉ“+¾›˜˜\¾¥|¶Ý»w+Î:lUââ@ûòåK®£((§§§'‘HrssE"QãÆH§$Deð¯“'™›7‹mmMÒÓ›Mœ˜?iTt]fR}JVÔ?->>Àüùó¥—¬•©‡­¢ºuK54Ô²²ö¬ZÅu…Æãñöïßçææ–`oo ‘H¸ÎEˆLyzª?xp³];>ÃènÜ(lÑ"æèQ®3E¤REýáÇ^¼x±~ýz(W[E SX¯»ÒR®£(† ¸ÿ>Ã0B¡ÇãåççSi'ªDMG§íÌ… ¨WO#&¦¡¯o술ääßTª¨?zôHúbÉ’%[¶lQ²¶ ½¼ kÚ”ë JÃ××766vÕªUÚ¶mûøñc®C"S]º”FFÞnÜX p߿ݻ§GEq‰(Õ)êEEEå·Ÿ³³³¥7Ý•¨‡­ÎÎ^œ;WF÷ϪÌÎÎÎØØ833óúõë±±±ÒGåÅ´HQ!SÓÖÑÑÅ{÷ÂÄ—. <<® Êu(¢(T§¨'$$¼¹µ´´´N:çÏŸŸ9sæîÝ»ÃÃÃs”nÊUggñý•HË”}!ccãøøø³gÏÚÚÚFEE5lØðرc\‡"D–´FŽÄƒñ êß>ŒÁƒ‘™Éu(™IOO÷ððèÛ·/×A”êõòkïå Oœ8±|ùr??¿Ö­[º»»‡‡‡sïk¸¸h¦©I­ê_AGGÇÛÛÀ–-[’’’îܹÃu"BdÍÜÜ)!áÑÌ™ÐÑÁ±cÙVVçøëL²±hÑ¢¨¨(‘HÄuå£:E]úèûÇèèèÌ;÷æÍ›­Zµ’[¤ê²³ƒ††™PØÌÁë(JlãÆ;vì˜;w.€Aƒ-Y²„ngUâ¼t)bb2\\ KK»mØP6f ¸U]ÒÑ—t)NòET§¨K}¯HKK+(((99yþüùzzzrNU-|¾ÄÁ,±?×Q”Ç3fŒŽŽÎ;wŽ?þûï¿gÑLÚDÅ4h`5d«¦¦¾kW‘ƒÃ? p©Z^¼xann>pà@®ƒ(Õ)ê/¿«©©ùûû'&&.[¶ÌÐГTÕ”enàôŠ\Q-[¶üçŸvìØann~ùòe___𩆍>¿Ù¡C¼¨(±»»vjª÷¼yÏ|}¡œ ±b±8---00Pºpù"*RÔÅbñ³÷éÓçÞ½{[¶l±¶¶æ*Uõi7o µ¾>×ATDÇŽ `ÆŒG•Î2Kˆêpsã…‡ÇôìÉ0ŒÝÑ£lóæ‘;vpé‹¥§§ ‚‰'rD)©HQOJJ*))‘¾nÛ¶í7N:åîîÎmªê“õ¶¶\Q5G?~üO?ý$‘H&L˜@Ñ•Áhi5>{– æÁ×qã.wë¦PsÔäææ®X±¢_¿~ãÇ6lX=>¸yšžž>räH333®*7V%œ:u €››[HH×Y>Oº¾Ü‚ >¿kL äZX$$$Ô|®ÚhçÎlllJKK¹ÎBˆLåæ>lßžX€õòJ»u‹ë@,˲'Ož477 *))aY¶  @CCÃÚÚZ$qME¨ÈH½¤¤dïÞ½ÑÑѪÖר¨‘„aê¼}{>$„ë(ªiÈ!AAAüñ‡ººú™3gh©7¢:ôôœ¯_/¿|»Á¦M›ÆŽ+Ï0ªŠº¢“8:¸»w/×ATœ´ýĉ<ï?þøá‡h¼NT‰íôéÌýû%­[ëú믒~ý Ç™³×¯_Ÿ––foo¯|«`+*ꊎqqðìÌ™ììl®³ÔíÚµswwÿùçŸ\¹r…ÚÙ‰Š°µÕ {>uªXMMÿ‘›Ûþñãå3ëáÇPE¯"±XܱcG@ð~cέ[·AçÎ?½¨4uEǸºð61¡iåÆËË+**ªK—.iii¾¾¾ÎÎδ¦Q Sÿ?øÑÑððP{õjØöímÛ¢†/Å …˜˜nnn5z"•Áçópà÷©ÂME]á99a,óóMŒ¸ŽR‹Hoû1 ÓµkWOOφ „……q‹YpqAxøÓ#X†i}çš7¿³y3˲5t¶´´4é SSÓ:…ê±´´Ü¿rr²ôY„Q£F½zõêÀæŸ{¾ŠŠºÂÓÕYX@(¼ºs'×QjSSÓƒJgAX°`A»ví–/_Îu(BdAMÍ~ß>Þ­[hÔqqÍ&L8ääÄÖÌå@mmm鋌ŒŒÞÊÊÊJII©‰“ª€.]ºÌ™3çĉ:t8{öìo¿ýÖ©S§Ï~ŠŠºÈ43psûv®ƒÔRššš444AÇŽ<~ü¸æ†5„ÈO«V¸?©o_5ໄ¦}ûü{÷d~cccGGG!ÿžoãõë×ÒŸ/R©¹sç¶nÝ:44´S§N³gÏ®ÊG¨¨+M]ëÖå:H­¶pᤤ¤V­Z%''·hÑ¢C‡ÅÅÅ\‡"¤Ú´´„„ä> kkܾ-ðôÜÙ¤IVf¦lO²xñb†aΟ??}úôÄÄÄgÏžýùçŸ~~~«V­211‘í¹TÉ“'Oâââ<{ö,77·*¡¢®ô[·ÐRW—ë µ¥¥%€¤¤$kkk--­ÜÜÜ¢¢"®sR]¾¾xð §O ‰dLLŒÞ!xõJ†Ç8pàéÓ§Ûµk·iÓ¦æÍ›<¸¬¬,$$¤^½z2<‹Š)))ñõõeYöÏ?ÿ|ùò¥ŸŸ_•>Æñ4µµÒÌý.uý: ¼´´|ñâEMæ"U•––Ʋ¬¿¿ýúõCCC¹NDˆlälÛ&Ò×gÒ:u¶x{çæær¨öò÷÷̲¬ôÚûêÕ«?û)©+úoÞÜ¥Åă©©iIIIDDÄ›7o¤×«xqŒE¦?n?>žíÙS½°ÐÿúõÌΑ•Åu¨ÚèСC[·n7nÜðáÃÌŸ?¿C‡AAAŸ]R’Šº206.ÑÕÕ\iauE¢©©yçÎ7n8::ÆÅÅÙØØH§‘'D¹YX0gÎd.YRª®Þ "‚uuÝíëK³ÊSbb¢¿¿¿»»ûºuë¤[ø|þ Ê;×?†ŠºrÐlÖ €=q­`ø|¾§§'€'Näåå=þ€X,æ8!ÕÄ0Æ¿ü"ˆGÛ¶ÌÛ·ß=æîŽÂB®cÕ 6ÌËË‹‰‰ÑÒÒ*ßhee•–––””d``ð‰ÏRQW%vv.­_ÏuR¹Ù³gÿý÷ßK–,0tèЀ€šÖ—(=;;\½šöÓO"†éùò%Z´ˆÙ¹“š>uåÀ:9H>ž¥Áº¢êÑ£‡‘‘ѳgÏΞ={àÀüü|®Rmjjf«V©‡‡ÃÉ ññ.cÇ×­›•šÊu,òQTÔ•ƒ–‡€^õëÓ ð ÎÎÎ.66vß¾}666ááá^^^ÒY¯ QbžžˆŠJ3†ŒÏÊ2êÛ·äþý²²2®c‘JPQWÎÎ,²³ÕÕÕ¹ŽB>ÃÎÎîÛo¿°`Á‚[·nI×§"D¹ijšîØ!:sFbm»wùžž›4xÇu,Õ·fÍšµk×–””Tq*êJ¢n]Q:ÈÈ8ÌuRU‡Z´hѯ¿þ `ìØ±Çç:!Õ"èÕ‹W:z´ºHôã«WõÆÃË—\‡Rq¾¾¾3gÎlܸñîÝ»«r¥–Šz‹ˆˆ¨Ê¤c………÷>9ër†±1€¸cÇd–ŒÔ0]]ÝÙ³gkii>}zçÎ&L ¾ ¢ôôõ»vïÝ[ª§§sû¶ÄÕu›[RR×±T–••U@@@bb¢ŸŸŸ££ãŽ;>}ナz“H$ööö«W¯þXi/,,\±b…½½ý§WÉ•Î?ÐÙ¹FR’šÔ«W¯M›6­[·N__ÿÒ¥KK—.¥û‘D©i)HH@ß¾¼üüÉqqY;CÖÓÅ“rAAAÒÞ¶gÏž7®Q£F[¶l)--­tg*ê5®eË–?ÿü³½½ýš5kÞo)**Zµj•]PP——WÓ¦M?qƒ6mØÒLãJˆÇã:T$Mš4iÖ¬Y;vìà:!ÕcnŽü?ÿª«7OJ‚«ë退·oßrKYZZ”ùüùóÀÀ@‡ 6…Â÷®ñék ˾?±Ÿ••U=ôìÙ³|¹{8µrƒ IDAT†aîß¿ÿ™£„„°À}3³œœ¹¤&5âÒ¥K¾¾¾¥¥¥"‘(((èõë×\'"¤zž=c½½Y€ ¾½zeeeqIÕ¤§§ëèèT¬÷&&&óæÍ{¿(0,õ=ËEï޽Ϟ=û±w ðŸÿüç3‡xò ¦/ÃÂÚ´i#ã|DîÖ¯_?yòdww÷èèh†a¸ŽCÈ×ÊÍETTÉÂ…W®$SÔ­«Û¢äÕª#‹óòòäs®r‰DÎȤ¤¤¤~d† ‹Y³fùûûkhhPQ—55µŠ3ƒZ[[§¤¤”y÷îÝ–-[Vúq†a¢¢¢š4iò™ÓH$b--~iiÆ“'&ööÕ‹L¸÷ìÙ³‰'úûûûøø\ºtÉÐаyóæ\‡"äsŠ‹‰‡‡ÈHɃ¼ÿÖ¶WÀb`·ñj«=z,[¶¬I“&TÔeàÂ… ‰¤üË»wïÎ;·mÛ¶¡¡¡ïïö±Áz•†éRMš &ááøÈßDåä丸¸¤¦¦†††Ò5¢p²³ØXÄÄ :qqø÷“=e€š«kDié¦ÄÄ]€#°ÐÎ&ÀÖeer¯óù|==½š>Ëx<ž¾W؉D>>>¯_¿®øV¯^½æÍ›÷¿A#WwTÕóçÏÍÍÍ¥ÃôÞºwï^Å«¬</..®ŠÏíÕ‹vï.ëÔ„K………AAA:u’H$%%%ÇŽã:©Å Ù7Ø5kX¡§g™ŽŽôfùÿþãñâùü#@î´ilHÈPooŸ½{÷èÆ0<‚w‡Šg-,Ø;9ý~TÄû֖ב^½z…‡‡°'uYÊÍÍuuuÕÑÑ‰ŠŠªt‡þýûPÔ}}}«~üÔI“X`«¡¡Œò"‰X–]¸p!€‰'r‡Ô ûà{ä;oÛ§kg'áñ>¨â"CC¶K—¦¦£€˜]»Ø¼¼­[·—?œõêÕ+mm´°¶~wð… Y€0€•H8ûU‚P(´±±y(8räÈØØØJwV«Îò>‘H4hРøøø“'O~¬9mÞ¼y!!!ìoyðx¼yóæUý†^^ذa ‹‹ âÃçóÔ«WÏÌÌlèС¢¢¢\\\4448É‘œœ\þ¥¡¡aFFFqq±D"ÑÐÐ011qtt”ÿeOR-……ˆŠBd¤86¶$2RûÙ3æß˜± ó0èÜÙªk×ÕçÎý“—7oË–-Z4Ž‹ë`hhee`üøñåûK$’Ñ£Ggddôõö¶¹u €ÀÊêÝ{¿þ [[øø€apò$zö„@ ¿ïT…ìß¿¿ü‡±gÏžóæÍkÕªÕÇv¦{ê2ãïï¿mÛ¶õë×ÿðߨíý;ë_p7]*.nnpp@bbu¢EVRR¢©©™ššêììlllfjj*ÿ‰äåË—‘‘‘Ò/ù|~ƒ ŒŒŒø|þãdz²²¤Û´icff&ÿx¤J$ˆ[\\üöí[«ò+®Dž¤ñÈH<|XÎÜ»W'/(ÿs¬@W÷j~¾zëÖÝúézFÆ¥ää¾>>æžžÝîÿÝ§Šƒò >\(Ž7n€·7JJnòxx¯è\]==¡OÌœ‰nݾ⌵“——׈#ª¾?õêJNN9r¤Á¨Q£.\¸P¾]SS³cÇŽ•~dÞ¼yçΛ;wîçž CÃ÷7h4mŠ+W†¸»€XŒ¥K1>ú÷Gw^IÍQWW711‘H$……… 4ðæÍ9Ù+¥¯¯_Þ]“™™IE]NÒÓ]ÉFDh=|(IHàýwÙ.édc¥|¾ uë'{#"ì½ref^žÑ«W®®®Ð×÷¼e—eúôé=rrrZ³fMÚÚµfeeLË–xoöÌ‘^õÙ¾ÿüƒädV­ÕjÕJ­Zg]€»Ö=±Š£¸¥ˆˆŠ("DVX!dÞçXJQ‘ä&á¼_¿?àææÜÏÏòåÞœï9‡Ã3fLõã5Ÿ©®k×®{öì©{¥÷ŽÃáÃ6 Æ¡cGzݺáæMýœdfbÊܽ #F4ý!ä“É›Íf2™âùttåÏÕ«ÏÏJâÖ-ôí+Åñß¿çݿώ‰1ÌÉáFE©¤¤¨Rm@[|‚ŽÛÉéÄD57·™›6•ØÚæ&'·oßff­€ÕRLö999Ö®]ëîîžëÃãñ Ý!C°cG]ïd0°f <tïŽ PíD¢éHQ—o öïG§NÈÉAJ ¶lÿ*íÈf£êö¨wïè e5mÚ4777ñló¹s禦¦†……‰ë½ŒUÿCö“Ï ^¾|™ýÅ_È0”4•—cî\èèH²¨s¹xñ‚—®˜h^TKw}i" IUÕyâÄ {û]·n™ 0ã‡t€ªíºô~ÕÚ—e£ª‡Í××wñâŬ££ýüð©G>­¼ZZ°° ]âHQ—{&&8||z ȳ÷æE<½¨¨èÚµkÅÅÅjjj„Baõ[g¨¾üÇôïÞ½{óæ¶¶¶,#IÑë×7Ïžáüù&óî]ÉúÉÉ‚gÏònÝjYZª"©U™RÆÆ7‹Šr &oÙ‚víνxáäîŽN´%â\9°mÛ¶¿þúËØØøðáÃL&“ÇãnÛf¨OÚ€QºwGl,Ľš?ý„ð¹N-¢žHQW~~øö[lÚô‰— |´J¡ôŒŒŒ^¾|ùðáC{{ûçÏŸ=zÛ¶mƒ–Y€Šj«T‰Íf§¤¤XYY±Ä)ºcÇ6ðókÀ9êñã×çÏóŸ>íÀãáåK°XâµÂUK@Û´QéÚõÈË—\GÇ)ëÖi:8ôàr«þHÓ¥‹äœ¦©ÞÃfeeàþÉ“}Þ¼á2™#FàùóŒem .`Õ*lÝŠ´4Èp)u%FŠº‚øåÜ¿GjïÚõÃD3c``0hÐ Û·oóæÍÕ«WeYÔ Ä_0Œê³ñ…Ba\\œ‡‡Gbb¢ÌÂH‹ø‘û|ø¶oߺ/?y¢—™ÉŒ‹{vâ„~V–—Ë\ªP ¢¯®îùå—úÝ»ß,)iáîÞ©Kuõêw¸t- Xÿéa9R|Ð.&† d¶kçØ¢Ecõ÷ÇܹèÙúú(-Y °ÉHQWªª8z;£Æ¶ÁäÙ{³ÒµkWñʲcÆŒqww_²d‰š4û… ªîÂíììª?fúôi›6m´”àƒÒ¤$Œ‡øø øŸ**2ÃÃóïÜih¼xQmðÏ„Añ="uu¦‡GtYY²¾~¿%K,üüZhkûþS³ûÉâg°E‹Uõ°Ulýø1Ç~hä jjؽX,øø }{:¥ùà†¤¨+lߎ3þsõfOUUUÜL}öìÙÈÈÈ™3gšKzyA6›ýàÁmmmŠ¢ªz5MMM«–™’’¢««KË¢¶¶};¾ÿ••Õ UNŸ~zô¨(&¦=“©ž›k#Øüóª.Ê`ètéb6hPlee‰•Uçñã Í̺UŸËï=x=„‡‡‡„„ˆ{ØtttÄ=êýð!¥¥Å:´©HJBv6ðx¤¨7)ê eút„‡ãÂ…ß:9ÁÅ¥Î7ÍH·nÝ""" ÍÍÍïß¿äÈ‘õë×J¨3BMMM(fggóù|UUUccc[[ÛV­ZUíYTT”ŸŸÿÙ…©å]e%.DHHÃ@uð`ÿ..¡¢Rhf–¤¡a5x°­¿‰MÛ¶ªªªéäÉ“ëׯ_¼x1EQß|óM```õçä ª­£ò:tp©öÜèåË—%%%Ý»w—ÃÏ×+**µ´´Ú¶m{àÀeË–­mßÞ뫯ÔÿûȽ:Cwwœ8aÃdÚÔv†’ªÑÃöï oÞè¼z}}ã5³}–«+† A‹hÕ "Ù¦¡Èÿ^ È×·$0Phj:ø§Ÿ>2Ñ,988„……ijjþñÇ;wî2dHõÎòFøì²‰ZZZzÕ¨««‹÷y“ꔽúKHHX¶lÙ>|ØÓÓsÓ¦M455óòò’““Ñ®]áüù™ÎÎTm¯]Ãúõ²Ì,ªzØöíÛ'îa«rnâDì~ý Ù• 55qò$BC`æLÌŸæ³d¡$¢® vîT fÈv½B 6láÂ…[¶lQSS»yóæ…ª JŠÇã½xñ"&&À½{÷Ú´i3~üxiiiëׯ?~ü8.]ºˆ÷É:thFFÆñãÇѾ½Å¦M6¯_3 qö,fÍÂÇç¬Zõa·…æ¡zÛˆÿÎÉ-//wzòWsu™L¨©!!'OâȤ¤HþʋшuË Ú¥¥¥ùùùijj¾xñ‚î,„b`³ÙíÛ·OKK;{öl}¶p‰DYYY?«¥¥åã㣫«+‡[§¿{÷.,,LEEeÅŠ÷îÝëÕ«W×®]£££ãããÝÜÜ\\\óòò:äáááëë[ßq) qqˆˆÀ¥Kˆ‰ù°¤£•ââ 3üëaîܹ!!!...?®šñþÁË—h׎«££ÁbUí·åãããííýàÁÉ$xô%%0oßBM 2_W‘¢®¸\®ŽŽŽººzII‰œ<Þ$äœH$ =}úô_ýEQÔþýûgΜYÇ?žØØØôôôMLLêž.'m………éééîîîÙÙÙ“'O …÷îÝKKK³···°°ÈÉÉ),,߈Ÿ>}šÏçÇÇÇ»ººÖ,HŸ«Wqù2®]C·nˆˆPúÏzÃÃÃGŒ¡®®þðáÃê3ÞÅxË—«ÿò fÌÀU%_ÔÅŠ‹Ñ½;X,ܸA¦ÄE(¦¤¤$Gw B!‰ñ÷÷§;Èçq¹ÜÐÐÐåË—S%^ÆNWWW$q8UUUUUU‡#‰/^¼wï^‘H$õ@<uãõö­Ô/D«ììl6løøÕÂÂÂ× #"ª×rooo §)*¢¾ø‚òð Øl ¬ŒHQWl•••tG Odd¤««kDDEQ7oÞÌÉÉ¡;EQTiiitt´H$‰Dƒ jÕªUee¥P(ßgRÕ©S§~ýú‰¿Ž‰‰)**¢;µ …âíõ|}}…BáÇ'<س‡XêêŸÿŸãR*êEñùTAEQÔP¿ü"ùñ•)êŠjÛ¶mzzzÁÁÁt!’@  (ª°°ÐÔÔT__ÿõë×´ÄøóÏ?—/_Îb±(Н!ŸššJQT›6m<{öŒ¢¨+VlÙ²E|!›7o`llœ••õé3–/§€â j–bQ{÷ŽÒÖ¦*2RZ—P|¤O]QµhÑ¢´´ôãO= ¢>Ä[µr8www‡ãääTYYùúõëN:U?­°°°¬¬ÌÖÖ¶éóãÒÓÓMMMµµµ—-[ùûï¿»ºº®Y³æñãÇìÙ³§›››Aaaa«V­<¨¯¯ïää`íÚµM¼4Quô°‰è>¬èÉ:œ¹9ŽCL |}Áf£¼-[Ê:ƒÜ#E]QM˜0aÔ¨Q5v½$ˆ±²²ºzõjII ƒÁ^¿~½xÉ@pôèÑôôtñš3 COOo„ wyÕîÑ£GQQQC‡urrò÷÷ˆˆ¸té’¿¿RRÒãÇãââ\]]§OŸ>`Àñ°UïíÞ½{íÒRÕÃ8¢–^µ¿þ:.;»X[Û woÇ€áÃ1|8D"LЧOA–Ê®AÉ'p*1mmmƒ‚‚Šô/M£¯¯€ÉdªªªöìÙ³²²róæÍ©©©ÕW‘+)) {ûöí'Gxÿþ}QQ€=z„‡‡ ]´hÑ­[·´iÓÆÞÞ^¼ ûªU«bccÅmuóçÏvtt”þOI|^Õ>l[·n­íÇØXù={Ò9ÿ¿¬ 99(,„PH[yEŠºëСƒ©©iff&ÝAeðÓO?¥¦¦vëÖíôéÓ§j§ü³œEQ'OžIKK;qℸ‹}éÒ¥æææûöí““óàÁññþýûˆ¡oÙ²%%%eìØ±:vìèîî®)ÙeȈ&ûä>l5Q”{R€ÖË—Ë4\ úú¸y‘‘h×ññ £3Œœ!E]™˜˜èééUíƒIM$~ ž––†O­ Ë`0x<ž¸®Ÿ:ujâĉGŽàè訣£S^^`Ò¤IóæÍ0qâĽ{÷öíÛW¶?ѵíÃVCÔ–-È̤lm™={Ê0ݧhk£K°Ù6 ³gãøqšóÈ ò™º‹ˆˆÃÝ2…V^^.¬å‘¦¸ÌçççèÑ£ÇäÉ“½¼¼LŸ>}Ö¬Yâ™t....ä3NESÇ>l5dnÚ ¹S'§jr褣ƒõëqàFŽ. ½m½¢®À´´´ÊËË‹ŠŠlÉꉄ„>·y†xF´······øYÓPÑÕºÛ‰ø|6€ÝwßÉ0ÝçLœˆ‰`Ë„„àâÅf>uŽuvûöí~ýúõêÕëöíÛõ|ËãÇ322ª¾500044,((/Ë¥¡¡abbÒ¦M===©$&䞃Q×êÑööö²ÌCHÛg{ت0>Ô-+CëÖê=zÈ*]½ñx8xÉÉxñ¢™uò™ºsppPQQ©íaé'¹»»{xxT}[VV¦¢¢âêêÚ¥K‡“™™yëÖ­¼¼<)ä%C}kªªªMÜ—+õéa«rkÎilËÖtêê¸GbÌ”—ãêUºцufccÃf³ïÝ»Wÿ·ˆ·¸®úV[[»cÇŽÖÖÖÝ»w/H" ccc«·3ÍÊ„ TUU0>úÜtðàÁr¸KÑhU=lâíêß>1Æ—E²FÐ×Çĉ‰0e ÆÞ½t¢ùïS1 &“™ššZZZÚôÑ444Zþ³<‡ÃÉÍÍmú˜„"ÒÓÓûꫯŒŒŒª?„WWW7n\ó¢ …S½‡M[[»î“³²L–¹¹j—.²‰×HL&||`f??º£ÐƒuÅ6}út‡sçÎId4ñ"$b………“P,\.wΜ9,ë›o¾ùöÛoGŒ1pàÀÙ³g/_¾¼mÛ¶t§#$¦ž=lU4.\`(õdM·d ’’`o¨(ôí‹ü|ºÉ)êŠÍÅÅÅÎÎî³3–ë©zƒ›Í–Ș„bÙ¸qchhè˜1c(ŠÒÓÓsssóòòjÐê°„ü«›Ø‹'OJÄû¦Ëí³÷ôô@Qøßÿpû6¶o§;L‘ÙïŠmÅŠ+V¬ÔhâÏÔÅ$õ‡¡X,Xžž>{öì?P'”ÆÖ­[ëÓÃVåÅöííE¢wFFíÚÉ žd0¸xëÖaÕ*Pž=Ã7+RV¤¨+<‹õöí[OOϦUý3ÔªÿÔŸ}úÈÍͽsçNÇŽíìì$ž ¥¥e||ü«W¯ÌÍÍéÎBHKC{ØÄ„BaƯ¿vòúöU¶Ž—+WP^Ž„ºsH)ê ¯[·noÞ¼iÜ{µ´´zõêUÿóÍÍÍÍÌÌIQW•••={öœ2eÊ‚ ºvíJwBZÑÃ&Vœ‘1€Ïf_}%µt4Ù´ >>>…0m”eªyŽª Þ¼ysæÌ™ªOÄëï³»¶ðx¼ëÅ2™L².r8sæÌãÇ7oÞ\½ëP2èa«büð¡šPÈìÑÖÖRŠG§‘#Ádbõj`ìXºÓH ¹SWx¯^½ )))]»vuss«ç{ëØ6[ŒÏç'''˜÷Z^^ž››ÛªU«¦&äÄ”)S*++ë?šP8èaãóùoV­j ÅY¶qÆŒÁ‘#˜7D"(þ„!RÔÛ©S§ŵ™ÏçWTT„‡‡ÇÆÆÎš5K"ã«««s¹ÜÛ·okjjàr¹...ŽâæBaUTTìܹsÁ‚âéЄ²j\›Ø³gû&'‹ æ˜1RŠ':t@b"44“ƒþý±};|}éÎÔ$¤¨+°«W¯VUô*Eeffž8qb„ ¿E$U_N ”––êêêÖ6wFMM­Aº aÉ’%»w‹;~ü8ÝYi©êa nÄž¹YY@޳³¥ÒÏ ¯ž¹g°f úõƒ"o|@Šº‹‰‰©íùùëׯy<žººzãqqqéééUßr8œÈÈHR¹›•ÀÀÀ˜˜ñä)B)Uïa[´hQ#F0½y€åÂ…’Ž&¯Ö¬¦&f̓»wáãƒj\)RÔÕ»wï„B!ƒÁød]§(*11±ÓG»yxxxxxÈ$ ! ËÊÊÜÜÜþþûoº³RÔ¸¶*‘'Oö½v©ªÊ=Zñä“ ñŸ¹W®`èP €‹±®+ü¤€fK<׽ޙnÅÅÅ2ŒC(†yóæuêÔ)""‚î Ä¿nß¾Í`0~üñÇÇçÎË`0:`£{ت¤nÞ¬"¥98ÀĤoWlºº0¸ IDAT2RÜ;uRÔ•xFz›^É0¡*+++++´mÛ–î,Ä¿úôéãâârðàA¡PXu°¢¢âرc={ötuumÐhMéa«ò¥¦&ý  Æ½]±õì‰çϱl„Bàñcº5 )ꊪeË–ªªªµÝ©3Œ†þ. ”—ËÕÔÔ7G¦Dy3{ö쬬¬«W¯V9qâDiiiPÃËj£{ت²³Õ£¢ ¡a$¡&ÅÓ²% „„`ÿ~Œ Ill-3¤¨+0///Ôr³îèèúÙ6t¢™‰Dýû÷ ,++#‰rèË/¿ÔÒÒÚ»woÕ‘½{÷i`;YSzت6 BaI×®øgÿåf*(óçãØ1¨«#7—î4õEŠºóóóûäsT›¯¾úê矖}*BÅݾíÁçóéÎB|‚¡¡áøñã/_¾üîÝ;/^¼xôèÑÔ©SÅëCÔS{ØÄø|~»/ˆ”h‘µFRSÃÎèÞiipwǬY qËNf¿+¶qãÆeeeݹs§°°P${yy999µlÙ²¸¸xöìÙJKKÉ\ÍŸ½{=Ö¬qöòýóÏd¦…Üš3gΡC‡<¸|ùò°°0 zö^ÕÃæçç׸61µ¼‰<~WZâæÔK—.FGGÓ‡­»wѽ;ÆŽe$'‹P­[Ó›ˆø¬9s椤¤Ì;—Åb5è6½z[ãvac±X9[·àÕèA”SÇŽ04Ä•+øæôì‰Oîžõð!~ùEæÉ>B÷_„Ô={V$ñùü+V°X,ºãRKùù}¸;¯þäiÜ+++kÑ¢CCC‡SÏw±Ùlq«K```<»xQT¨¨Plv#Þ®Ìwêbl65r$µ~=EQTeeÍWƒƒ)€Š—}®êȺò5jƒÁøé§Ÿ‚ƒƒÝ·J(€·o1n<=ù‰Wœdˆh]]Ý)S¦hйo¿ý¶‰=lU:¼zÅÔFŒÙ¸ï“´µqæ –.‡þý±`ªïC}÷.ìØAW:1RÔ›‹3fx{{¯[·Àû÷ïéŽCHTi)~ø:àôi|²QU¶¶2E4˜x¿ñ×ú8}úthhh{ØÄòóó wï :yrSÆQrâ5w££ððŸÃóx¸Ž­¿`IQo.ìíínUýäªÏ999óæÍCÓzت\ßµË8-­BM ƒ5q(å׳'nÜÀÅ‹05Et4²²‹Š àr±oÑHK[³óðáÃâââ„„„Fló@ÈŠ‚Ÿ’‚äd¼yƒ¤$¼}‹ýèäÙ»|{úôéóçÏ>\RR²råÊO˜;wî±cǪ¯4%©¶*]ÓÒäyyµjHs|óåãoßÂßêêøòË_ ÃÒ¥P¥§¼’¢ÞìŒ?ÞÜܼ}ûöL&sÇŽ>>>MÿŸ šQm‘8J$zffÖ©°L&D¢GÉ*ròí?þؼy³••ÕöíÛýüüj¼ÊårOŸ>=zôèê ̉÷a311iÜ>lszò@«¥K›>T3bfèêâéÓfd <tmpGï<=‚F‘‘‘ CWW7//î,„Ä”SÀ{&“=eÊ¿Sß·o§;Ñx Úµk'ÄGž|8Ýqˆúb¿Ïuu5b±ðÝwذ¡æËëÖaùr:r@Q”žž^yyyãfffmÛ¶mÓ¦‹‹‹««k›6mììì ßF,åí[8::‚¿þRýhâ}ƒDEEùøøx{{‹gÌ5/B!âãq÷.n߯ýûîÑmm‘’Y!Eøƒ¾9xp]J åáQÑ®NŸ>èÒ††tç"êr§C‡Þ/^¤ØåæBC£æË|>¹SW\™™™¶Ÿ[ °K—.ëÖ­û¸®^?F—.CC­‚4­5®YõêD"$$àÎÜ»‡¯¿F²¼8yØBüÇŒ30czõb\¼¨sñâ‡M‡Ñ¥ <=Ñ¥ ÜÝ¡£CwL¢šˆˆÞ <&“{ðà'*:@*ºB«þìýc...ÁÁÁâý7~ÅÁƒÚ€Ö”)M¬èÄ¿˜Ltè€ðÕW²¿8)êÄ'—,Q¹wïßï““‘œŒãÇ@EmÛ~(ðžžèØñÓ…„‰¢7oôgÎT¡(õ œÉn=ʨjê{ ŽŽŽëÖ­3fL£Ë9€çÏžìÞ­ `üøFBÈò§ñ *C†P;~ú5¡ÏŸãàAÌ›‡~ý°jÕ‡ :$õé£òþ}a‡ÄB¡„ªšú^ÅÈÈè×_}öìÙØ±c›RѤŸ8aêêÂÛ»)ãòƒÜ©ŸÂ`0–.E›5™˜à›o0>ŒŒd‹øþï¿{åä”1ÜòìTYUü®££³`Á‚%K–Hdð!l6µ‰Ñ´?ùA~µ7Ÿ8nmmÛ–†•+IE§/9YmÁ¢Í›-Ém–òJLL ¦¦6wîÜ7oÞüüóÏ’ªè©©‚cÇèJd@B¢NÔBU‹×8&îvè€o¾!såè% ŸwíŠâbÁˆú Ò‡–âââ¼¼¼ &¼|ùr÷îÝüÊ?¨¡K KЋu¢v3gÂÒ²ê»2==!ÐëÊ  ‹Æ\DÖ÷ß{°XyLfÙÆtg!¤ˆË寯Æ?~ÜQ ûìuNJÀñ÷—øÈHQ'j§¡¯¿®ú®Å¨Q©û÷×/¿·³K §1Z³–`»s'€¼µk ÉFéJ­eË–nnnRZ èš‘À’<éQ.¤¨uš?ÿß•gºvuž9gÛÚ¶,+³9’:tˆÎlÍReYYjÏž¨¬ÄÌ™íÉ:qDcÝúñGäçÃՕѹ3ÝYI"E¨S‹˜=ûÃ×ⵦ--õž<¹âä¤IQŒ3J'Nq¹4ln¢‡ ³g±254¨íÛéÎB(*¡P˜»};€º³FŠ:ñ9 @SjjèÔI| …±ñ ¤$9Biié8ñÒ‚ýö-½›‹èèÞ÷ŠÝ»uïEµã•—¤(–dy¥CŠ:ñ9ææ@§NÐÔüÏñ)SžíÞ¡¢ÒžÅÒéÝÒ”¯¹`ef–€¹dI›™3éŽC(0­49´oº³FŠ:Q‹¡{÷wš>11‚~ý-ìÙ3žTiŠñõÕ}ÿþ½¹9~ú‰î,„wæÍ ;–î,„ä‘¢NÔC«VXºô“¯Øvî¬zýzv@C(ìtð`ùÈ‘dÕX©¸r¥r2—Á¨Ü¿Ÿ,¶O4ÅÍË—;§§`Ö±d$¡°HQ'êÇʪ֗TT¬öî½>oOKK÷Â~·n…Ë0™òc½}KÍšŠR ¶<˜î8„bëÁfëE­Z¡ukº³’GŠ:!wíRú”jÛVíÅ f·né{÷ÒHIPõÒLJñî]E×®ªßOwBáiÿù'£¹séBH)ê„ä8;^ºtËØØP$²›;«WC$¢;“Â+ õyÿ¾ŒÁ¨Øµ‹ìÚB4ÑÕ³g+Oƒ èÎBHùAH’‰½}œ–øø5kâíí¹ïßÓJ‘edè/[ tÍOOºÓ /34TS$ʱ¶†­-ÝY© E05uuÃõë¹—/0™22¸nnHH ;”Bâq¹1;¢¸˜5ÊjåJºãÊ  E :¤QEy‘¢NH…Æ€™çϧ™™éåæÂË+}Ó&º)žg³gw))ÉWQálÙBwBä¼zňˆ“©@wBZHQ'¤¥ó°a­22€òrÛ%Kû÷‡@@w(Å‘àyò$€üà`m;;ºÓÊàÌ—_¢²’Õ¶-¬­éÎBH )ê„4ihPaagû÷ç®ý??Øë¡œÅÊñóïÚÒ–Ìx'$¢(äd 2EN©‘¢NHƒÁ}íZ~x8lmqçNA«VyþIw(yw§ËÜÜ\]]üöÝY%Á`±|ÊË¡¢b@ž½+5RÔ Y°6 ?755©¬49¤‹½ÑуãâD FeHttèNC(¦“'AQÕÄ­Y½{£eKºB2@Š:!+¦¦–ÏŸ_ssS ô~ÀŠ,(û‘¼´4Þĉ ¡¹dI+²Š'Ñhׯ#  j¡‹•¿s'€Š¡CiEH)ê„ì·l9 .ÇŽ 55[^¿žncC¥¥ÑJ¾Äôë§žšZjoOvm!šÄÞàŸUËSR|)JÈdjO™Bo.BÚHQ'dnâÄ{6¤2™­ŠŠ]º 2’î@ò‚ñâàÔT.ƒÁ #»¶M"^×}Û6|÷›ØXŠRéß&&’ºBbbâÎ;¹\îgOÛ¼y³¤.J|)ê ú|óö«W1¢þý“fͪñù_3Ä}÷Nmî\Àûá ??ºã ®j³–_å,\øvÝ:?þ?ç”—£ Ê\]]O:ÕºuëÚJ{bbâ¤I“Ú·oïììÜè« Å šý/S‚6õ÷˜1žçÎ1ÑСÌ?þ€žÝ™è! o[Xøæç {ôP¹s‡¬ñN4UALM«¾£!“©úÛoÈÍEJ RSñö-¸\\»†nÝ}‘›7oúúú°±±Y¶lYÛ¶mûôéãíí}ðàÁµk×?~\(zzzþý÷ß C?Q¤¨t¢(êä—_޹pAµ¬¬ÒÎNtö¬¶‡Ý¡h¶~}«eËÊ™LÁãÇ;Ó‡P ()©õU}ý&Vt±Þ½{ß½{Wüµ¹¹ynn®™™Yaa¡P(üóÏ?‡ ÒÄ«õGŠ:!’“¹þþIIl&S°oŸþŒt’­Œ tê„ââÔ+ì×®¥; ¡,<<ðäɧ_24ĵkèÒ¥é¹uëV¿~ýj{•ܦËyÊGÈGÇÜðð?ŒtD"ýY³ðý÷øçÏ|¥WÉá<ïÚÅÅ=šTtB’?}ÜÂÔ³¢«ªª2>b]m•Ù¾}ûöêÕ«¶·¯ZµŠTt#wꄼ¨¨¨`îÛ§¹x1øü$Çèh¦äfêÊ­«C† ¼|¹PUÕ(;›afFwB‰,_Ž_~©yÐÒ7nÀÅ¥žc\¿~]ôO³;€˜˜˜üÑÇÇçþýûU£¢¢|||>~o=îÝ»×àØDÓ¢NÈ—¬ãÇU'M2xææê/Jä ¡üzýšêÜ™Áá$oÞìøí·t§!”Ëþý¨±"¬•nÞDc碧§§wëÖMUU5::ÚÊʪúK~~~7nܨqþ•+WظkF¿òÅzâÄÔÓ§óÕss©ž=ÓW­¢;‘´°òòŠdp8˜9“TtBòþó­…þú«Ñ½´´ÔßߟÍf_ºt©FEðÓGk%õèуTtZ;uB.q¹ÂE‹TvííïouîÔÕéÎ$aç:võüy‘‘‘QFYã¼ÌLØÚ~øÚÁ7o¢±{ø ‚Áƒß¼y3<<Üßßÿ“çÔ¸Y'·ét!wê„\ÒÐàoÚâãSÉ`X]¾Œ~ý“Cw&‰ŠŽ‘ È®-„”ä©©‰W„¡¬­qíZ£+:€yóæýõ×_Û¶m«­¢øá‡ª¾öôô0`@£/G4)ꄜÒÔÔœsÿ>ûúuØÛãÁƒ{{Ö¹st‡’Œ÷©©¢©S™"¾ýÖrìXºãÊÉÌÜ\ÍÉ©ÒÜœq÷n­3áëaãÆ{÷î]°`ÁW_}UÇiÕ§Á“Iï4"ß y'ÌË‹vpðf³EL&sÝ:,]Jw¢&‰DíìFdeU:;k>{FÖx'¤$&&¦Ë™3X¸ææäìÙ³cÇŽ:tèùó癟[èPܳNzÓéEŠ:¡Þee%MÚûÎPTvïÞVÐÖ¦;T#?®?iÁ¨¸{×°GºãÊ)11±mÛ¶î;ÇÖ¶þL=ddd¸¸¸hjjîÝ»W§Ú‡Dššš}úôùä[|}}/^e·mË>^ÆÒCBƼÏe08û÷“Š^ƒP(ìÓ§ººúßÿ]uðáÇêêê¾¾¾"ÅY"PÞôîÝûáÇ[·n¥;A'r§N(­Ü¤¤Øöíýù|ŠÉd¬\‰”Ñâ¬EEèÐ99Y_}e½c‡,®¨hÞ½{çææ¦­­g``PXXعsg>ŸÿôéÓ–-[ÒN!ñùüòòrCCCºƒ4#wê„Ò2wvv~ñ"~âD€5kr½¼PR"í‹r8œ;#'½{[oß.íË)( ‹£Gfdd̘1C$M›6-;;ûرc¤¢7Úõë×-,,/^Lw‚f¤¨ÊÌÉÙ¹Ó±cü³gKUTÌcbJ]\ Õ+^>Ý'#ƒ­¢B8@vm©ƒŸŸßÊ•+/\¸Ð»wˆÕ«W÷íÛ—îP ìéÓ§ÀØØ˜î ÍÈãw¢Y8´b…÷¦MÎ\.tuùaajRZP63;¢¸8sÕ*²ÄçˆD"ŸGõíÛ722’Iþjš¼¼<555ò¾™#Eh.¸……óçãäI ÈŸ0ÁìȨªJpü¢ÂBnïÞ =gÎHpde•””äééYVVfggGªQ£½zõJMM­µÌ»<9Dþ4&š ccêøñm®®ÀìÄ øùáý{ ŽÎÏÏ"!¡\G{öHpXeUYY9nÜ8Š¢vîÜ™™™9cÆ º)°U«V9::>|˜î ýHQ'šƒ1ïéÓÈᅦ¹9îÜ)kÓF%™¡_¿ž‘˜€ûÛod×–úX°`A|||HHÈüùó—-[Nz±ÍÜÜÜØØ˜LJ @¿ÍTvvš§g«Ü\ŠŠjHš2Xnf¦é°a*OŸ §MS!wKõpâĉ‰'ìÝ»€P(ôõõŠŠºÿ~×®]éN§ªD?N")êD3}÷îëáçàMŸ®Ú¸ W(Šú½uë/SSy¶¶ê ÐÕ•tReóæÍV­ZEGGkii‰æä丹¹éèèˆ;×éM¨XÂÂÂÚ¶mëããCvp!@Š:Ñœ‰D"æÑ£TP£²2ßÖÖôî]ØÙ5tÖÕ«zƒƒ¢Ê/_Ö‡ãéÓG;wÓÕªª"2ãÆ±ôõsçÌA~>½?"âñxkÖ¬©ú–Á`L:õùóç—/_&ý“Μ9Ãb±HE'>‰u¢ ƒ¹9öì//˜˜€Å€õëqú4ÜÜD"ÑôéÓ |}}'NœXý­^óç/.æ$&býú<Ê óÐPX[—̽|™ŽFQ=z4##Cüõ Aƒpf`= IDAT¢¢¢~ÿý÷öíÛÓ›Jn½zõjìØ±®®®B¡î,„<"Ehfââ0f –-CCàÑ#˜?¹¹¨~î¶mÛþúë/ccãÇ3?Z VEEEÏÑK—–ÅÅ…ŒÍ2B¡î•+C†pìí±};>êÑ"jëÖ­0hРGEDDtëÖîPrËåúûû1Bå¿«„ùLhŠ‹qìòò°z5þþݺÁÖii¨¨@Rj™?×½{w.—{îܹ‘#GFEEùøøx{{?xð ¶ë°“’Žõí;òÝ;ŠP©®žïëkõË/L2m»üñÇ~þùçîݻӅ ”¹S'”Wb"€ÃÁ×_cãF°ÙèÒ;wâÖ-0ÐÑ©­¢WTTLž<™ËåŒ9²žÔqvÌήHJ©SEîîš<žÍ•+L77Êã"$|¾¤~2¥áíí}óæMRÑëéõë×?þøãóçÏéBÈ/RÔ åBQˆŽ†P^^˜=©©°°ÀÂ…øí70`00>êfñâʼn‰‰...Û¶mkh[GGŒˈŒÜ¿xñ³>} «ËxòD{î\¶‘¾ÿééýÙ”ÃçþATwðàÁµk×îÝ»—î „ü"M8„Ràó!AC}úàî]ܾ޽1aÊÊ>ÜoÚTÿÁÂÃÃ÷ìÙ£®®~ôèQÆ%244œõë¯PV>a‚}DDÇòrlØ@mܘ۶­ñš5ê£FÁhÜàDó4bĈ &Є_äNP|¿þ 33œ< ^^°°@^„†âØ18;7h°œœœ€€k×®uww—@¼-†_¾¬“œ\q÷.‚‚x€EB‚ú˜1pv棠@— š//¯½{÷z{{Ó„_¤¨Šéþ}  ñ­°®.Š‹?Lb_µ YY;¶q£Vïa[¼x±äâ¢uëÖÚ={ wïþsǎî®”’“ÕV®ä·lÉ9µO¾#±•+WNž<™| NÔuBqäçcëVlÞ ¥¥¸t 'NÀ„ HHÀîÝ ­zÏê¯î¶¦SQQ3þ—/_2RR^íØq^UU…¢Ô.\@ïmlÊ6o›-ñ‹J€¢¨Ã‡;vìã½ì¢:ÒÒFȽøx<}Š/¿DBÚ·‡™rr `ÿ~ kkI]§F[WëÓÒÖP,+÷Á×û÷9;wj‰Ë¹¾>5ncÁ´k'©«Ê!111<<|éÒ¥ 2ƒ¨)ê„\ ñ÷ßèÞ,Z¶€¼<`Þ`0(€(&³ÈÃCtò$%4%!!‡„BaEEÝ)Å@îÔ I›;¦¦xüªªðô„ƒÃ‡}É®]Ch(ŒéÎ÷-=lùùùêêêóæÍ«ãH}¨¨¨@CC? @#&&|åJ‰44 ccãÇÃΫW#?_ÒÙ ÄÆÆž;w®²²RKK‹î,„b E„³gÑ·/Ο55TVâáC8zoÞ [7zÓ}LJ=l%%%7n6lX``à¤I“øòåËê'äççO:ÕÌ̬Ž# âáá1ü§Ÿz÷øñ[¶Ì56Fv6Ö¬˜›÷ïÈÈ&ý<Ý6oÞè~T@(¬·o©5k¨£G)Š¢6m¢jòdŠ¢¨Œ *=ÞhuËÎÎ611°aÆú¿ë³ßÃÃÃ[¶l¹téÒÊÊJŠ¢ÊËË544¬¬¬²z.‰***¨{÷¢¬­yâgò·ukîÆTY™l2’µk×.´´4ºƒ ƒu¢!„BêÞ=êüyŠ¢¨Ó§)€êу¢(*#ƒ:tH~>/¯ƒP(üâ‹/øúú …Âú¿±î¢¾gÏ&“¹dÉ’ª#×Å«èïÄS d(99yUPPÉòå”­­¸´ tt¨  êÙ3'!BÆHQ'ꡲ’Љ¡(Šúûo  lm)‘ˆ*+£fÌ ÂÃé×0›7o`llœ••Õ 7ÖQÔ/_¾Ìd2½¼¼ªß”³X¬9sæìÛ·¯©‰› ¬¸ø['§›**Ô?óéX­[‹¢x<SõôÓO?íØ±£¨¨ˆî „"!º(5‘ ½§Sy9tuQVðxÈχ¶6||àé‰õë¡­-Ѭ²PµÛùóçGŒÑ ÷Ö¶¡KYY™££c^^Þõë×ÅÏäMzzº—þãº'N|˜¦hnÎ0Aãÿƒ½ÙˆÚ”””˜››óùüììì–4õ|ŠˆL”S^æÎm|E?ÆÆHIA‹psCÛ¶Èȃ¨(üö›"VôŠŠŠÉ“'s¹ÜÀÀÀ†Vô:ìØ±#//¯uëÖòYÑØÙÙÁÉIo÷îß×­»6k¼½‘›«±meo/¾ÀŸ’%å円Æþýû—,YB*:Ñ dWG%%!0 {סC Ã/¿ wo¨©A(Ä£Gpp@d¤lZÕöU¼˜„œÅìÙÜ ¨qã4—.­ù¯ˆ¾É“';99©¨¨Ð„P<äN]‰°Ù9òߊÀÅÊË ;¦¦0úöEß¾?B!Z¶Ä† r¸è›¤Hu6ccã6mÚ¸xñbõã999sæÌÑÔÔ”ìå¤Êmðà…¹¹ï<À©S™mÚ¨WVjþþ;Ú·§üüpú4>Ú¶VIIøçÑl6›Ãáxyy‘M\ˆÆ »§Ž‚ÊÃúg1  ´´(0€ÒÔü°,L‡”¯/•MwVÙyò䉆†€óâsš ¶>õ3gÎ0 ‹-JJJzûöíŽ;ú÷‘ÑÄ+Ò(**jN¿~I£FQFFâN•FFÔÒ¥T}~¨§O)ww²†]£íÙ³GGGgÓ¦Mt!¹SW ,FlìZZBM ˜L<} Ož 2––4$¤ƒ”zØj=zô¥K—zôè±gϱcÇòùü‹/ÚØØHéŠ2н{÷=7n8=‹ìì•¶¶O¢"lØ rp(4‘‘uuÁâÉ|ù%D"FVñññæææt!Y|Fñåç£ÿe»†ÐP SS4Ë-žæÎâââ«ÝäÆúÚŸQz</""b„ ×.ÁÁƒþ%9;cæLÂȨæØlèêÀ·ßbófÙ†U¦¦¦dg6¢Ⱥ‚{÷}ú|º¢˜;·n5ÏŠ^½‡­é½9SWW1b<<òƒƒMœ¸·];88 ) ßÏ·´ÄìÙ5ÿùéè@<™`ËlÙBKfÅ—mkkK*:Ñ8¤¨+²¬,ôîÿnîù"fÍÂñã2Ì$¤×ÃÖœYZZî>v,ðÅ ¼ys*0ð4Àäñ†Î+Ú¶EX8œ§Vݾ/Y‚sçè ¬ˆæÍ›gkkIöÌ%‹uE¦®Ž;°iУLL>qŽPˆiÓpö¬ÌÃÑFª=l0™cBBt#"ÞDFbýúb]]íÄDÌž KK,X€ÔÔW8‰0mž<¡5®Âàóù­[·655íÞ½;ÝYEE>SW.xõ ¯^áõk¼|‰×¯‘–¡jj8}ÇÓO6oÞ¼xñbccãøøx+++I Ûl?Sÿ¬u+VäïØñ‹­­æ‹„L&ÃÐYXøïææˆŽ†­-mŠ@ PUü5 º¢®ì¸\¼~ׯ‘’‚  ¥Y$®6MÙ‡­n¤¨×A(ª¨¨>xp W¯ ‘Hÿã3Ú·ÇýûÐÿÄ+D•M›6yyyy{{K|A¢ù *; t숎éÎ! ²éa#>&^ûÌØÇgȨϋ’’šg¼x±cqùò‡6Kâ#/_¾\²d‰±±ñ»wïHQ'uByTíömÛ6º³4KW®¸Îž²²O¿ú×_˜3û÷Ë6“ÂÐÓÓ[´hÑÿÛ»û˜¦Î=àO¡•´P Œ:Úñ"–,""‚Û²_¸[$ƒ 3æN\2ðmjÜ$õÆL–‹/ Æ7TÔm.ŠÊxQy‘„0AŠÃQЂHÛsÿ8÷6„7eöôÀé÷ó×ÃéiûýCùñ<çùÃçóø»ÞŠ:pzØXvèIIyÅÝdÿóŸ¿D"»={Ìø <ÎËå™™™l§€I‹<ÀèacE‘-[ȺuC+:ŸOd2¢Tö«Õ÷}|úþùOò¯»páryYYKY'¨ÚÚÚˆˆˆú©Ço3u˜ôÐÃÆ²›7 Gþýo2mqv&..ÄÅ…8;“©Sé×íQBÑétGîÞíÔj}}})ŠJHHX¾|yDD.!Ÿ8qâòåËžžžË—/g; Ln(ê0éíÛ·¹ç°Á«…„×9ÑÑѱ¸¸¸³³S$]»víðáÃW¯^ ×ëõýõ—5ßí<99ÙÙÙ9((ˆí 0éá7 LnÕÕÕéé鄟~úÉŒ]éÀ©TJñ÷÷ÏÈÈHKKãóùgΜñòòÚ¶mÛÑØ¡×ëårù¦M›ÞçîÁbPÔaCÛä%‘H6oÞœ’’B©««ÓëõôLýüùóGí3ÝqÖ ¤§§Ï›7ïÚµkl.Àò;Lbèaã†Ý»w'$$Èd2Š¢ÒÓÓëêêW®\ÙÛÛk W®\©­­Å\À,0S‡É =l\âíí-‰ŒFcZZZDDDddäÀÀ€Oxx¸V«e;³îܹsùòeÜïÌE&%SÛîÝ»ÑÃÆ¶¶¶ÑÑÑ………|>ÿÞ½{Z­¶¥¥E,÷ôôdeeýùçŸl4¿‡ÚÙÙ…‡‡óx<¶³ ¨Ãä3¸‡mÓ¦MlÇF´´´;vŒräÈ‘ÔÔÔ˜˜BˆÁ``;šÙÆ… zzzj4¶³G ¨Ãäƒ6+!‘Hüüü!jµ:222))‰²sçNµZÍmeÆÉÉI(¢qÌ¿Y7nÜàñxû•’““y<^}}ýx?=lVhþüùçÏŸ§oÌRXXXYY9eÊBȹs猓H$Ÿ}öY^^^[[›»»{mmmyyùÆ…BáëzØ` ›6mòõõ¥÷XdeeýðûvíÚ²e Û¹Æ|ýúu¶S×`¦–””¤×ësss !‡"„ŒkíÝÔödÉô°Áp666K—.õõõ%„¸ºººººÒ3àÄÄį¾új6¸—””|÷ÝwMMMlΡ,ÂÏÏÏÛÛ[§ÓI$’   q½733“âââÒÚÚÊP¼W¢WtÙ ¯O¯×SÕÞÞ.ÁãÇ)Šºyó¦Á``;Úÿ¬^½š’‘‘Ávà,¿ƒ…$%%%%%%''wuukš>¸‡íí·ßf, p‡­­-!D&“•——WUUÑ}-ZäççWUU5úÇâââ!+V¬`;p –ßÁB¢££ßzë­£GJ$’¨¨¨×|zØàMøûûÓ[1ÚÛÛ EPPÇ»qãFlllUU‹Á>üðÃüüü3f°˜8 E,D$Ñ·ùŒ}ý-r_~ù%zØàÍ………Õ××gddB¾ÿþû¼¼¼K—.Bšššt:…Ã$&&®]»¶¹¹ÙÂß ÖE,‡¾ غuë^óüÓ§Oÿøãèa³àñxôãM333·mÛF_JHHxçwÊÊÊ,C§Óåçççææòù¸ú 懢ÒÓÓsøðáàààY³f yiÄgk>~üxýúõ=l`n^^^ß|ó››[oo¯Ñh4¾¾¾E%$$\¼xÑh42ú펎Žååå¸É10EwïÞ½cÇŽ­X±¢»»{ëÖ­ÃOHNN¦(jðô°888766ŠD¢¢¢¢ÜÜÜääd£Ñøòå˶¶6†¾T§ÓùúúÆÇÇ3ôù`åPÔqyyykÖ¬ihh8pàÀ’%K†¼Úßßúôé³gÏ>H?‡M*•â9lÀ4©TJ™;wnFFFZZŸÏ?{öìôéÓGüô iµZ77·ÈÈH.=@&\ÔÆeffÒæ#jjj2 ;vìX¾|9݉dêaËÉÉAX†D"Ù¼y3=®««Óëõnnn„'NtwwÇÆÆ:::¾ù·Ü½{w``@§ÓÑÿÔÌEXÖÐÐ@ùã?òóó׬YcêaKLLD°b×®]ñññ2™Œ¢¨;w644H¥ÒU«Võöö¾á†Í>øàÉ“'æŠ 06euuuô --­¯¯ÏÔöoß>vƒ5óöö‰DF£qË–-‘‘‘ …"<<|Ä}¯£»»ûþýûb±ØÇÇǼiLPÔe÷ïß§­­­)))èaƒ‰ÃÖÖ6::º°°P ÔÔÔtuuµ´´ˆÅâžžž¬¬¬ñN¸Ož<©T*7lØÀPZ‚åw`½üN;rä!$===l0ѨÕê––úŽ1GMMMýõ×_¯^½j0^óy¿T*U«Õ '«ÆÒJ`IEM:õùóçCŽËd²Y³f) ¥R©R© …——»·ì.--]°`A``à¤xV70ª¬¬lïÞ½kÖ¬Y±bÅöíÛ/]º”‘‘6ÚùmmmžžžEÑwa`fêÀ&F3¼¢B::::::nܸA سgÏôéÓ-œ `4óçÏ?þ<=.,,¬®®„sçÎÍž=Ûtɼ··7//¯­­Í4wrqq‰‰‰AQæàš:°iðÚûpJ¥òÌ™3·oßÞÝ0A”——wwwÇÅÅ©T*z‰þùóçû÷ï§Ÿúj:ùéÓ§dîÎ6(êÀ&ÓÖ÷!fΜyêÔ©ººº•+WN„eŒfÊ”)tïå‹/bbb–-[æåå¥Ñh8ðòåËáç †ãÇ[<&X ,¿›L[ßMœ¿þúë””úÙ“…««kvv6=.,,Ôëõ£ùìÙ³öövWWWKE+‚™:°iðò»££cZZZSSSjj**:LjK—.{rcc£Å€UÁLØT__Ok׮ݺu«»»;Û‰Ì`Œi: mGÀu`V«íèèøüóÏwíÚ5sæL¶ã˜‡‡7VÃ0º9€!(êÀšþþþÊÊJ???¶ƒ˜™ƒƒƒ““Óh7” …r¹Ü‘ÀJàš:°ÆÕÕ¸***jHãý#ÇûôÓOY ܇¢`~ñññ"‘ÈTÚ)Š …QQQ³fÍb7p–ßáé陚šÚÝÝÝØØh0Þ}÷ÝiÓ¦± 8E€ANNNóæÍc;X ,¿pŠ:G ¨pŠ:G`£€TTTŸ7Œ\.7°xñâàààÑÞ¾}ûvS?À¯\}ùòå­[·œœœAûÿiµZËÄ®ÂÍgÀz]¹reðtêîݻ۶m›>}úàs¾ýöÛ  oPPÞáM<{öL«Õ©ânnnlEÀ5uBinn~ÿý÷ù|þíÛ·=<<¿´dÉ’k×® 9ÿçŸ^ºt©ÂDg45MEEý£½½ý‚ D"‘馰€¢@zzz›››‹‹‹ýüü†¼ZZZ:d²T\\lÁ€0 TVV6779(•JǸ‚`v(ê`íôz}xxøõë×/\¸0ÚÆ·!“uLÓ`bºX»õë×ÿöÛoû÷ïc+{zzºi¬V«?úè#‹Du°j9997nüâ‹/Æ8mð6xlz€ Ëï`½Îž=õÉ'Ÿ¼r7SQQQhh¨Z­¾sçŠ:LL(ê`¥=z¤T*…BaNNŽ£££é¸P( ñ-aaa©©©ü±…"ŒŠ:X©ŠŠŠ€€€áÇ=<<4͈oihhP(˜¦À„…¢ÀØ(¯ÈUIDATÀ(êñ_¸@?â…¡iIEND®B`‚opengv/doc/addons/images/absolute_central.eps0000664016516101651610000006633213344612246020342 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/absolute_central.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 11:36:22 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 831 651 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -14.655400 -33.313802 translate %%EndProlog 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 42.525000 27.650000 m 33.890542 33.125056 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 34.084508 32.706041 m 33.796121 33.184928 l 34.352263 33.128305 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 42.500000 27.650000 m 33.342372 22.629297 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 33.802953 22.596705 m 33.244336 22.575549 l 33.562581 23.035135 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 42.550000 27.700000 m 42.550000 17.123607 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 42.800000 17.511803 m 42.550000 17.011803 l 42.300000 17.511803 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.117647 0.878431 1.000000 srgb n 42.504400 27.625000 m 31.249731 14.164345 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 31.690530 14.301797 m 31.178016 14.078572 l 31.306945 14.622518 l s gsave 32.178800 20.550300 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 1934 -128 1649 -32 conicto 1364 63 1183 230 conicto 1002 398 917 628 conicto 832 859 832 1130 conicto 832 4416 lineto 182 4416 lineto 182 4776 lineto 948 4992 lineto 1570 6144 lineto 2368 6144 lineto 2368 4992 lineto 3414 4992 lineto 3414 4416 lineto 2368 4416 lineto 2368 1211 lineto 2368 864 2512 688 conicto 2656 512 2891 512 conicto 3072 512 3250 538 conicto 3429 565 3584 597 conicto 3584 163 lineto 3509 110 3365 57 conicto 3222 4 3049 -35 conicto 2876 -75 2687 -101 conicto 2498 -128 2333 -128 conicto end_ol grestore gsave 32.655852 20.550300 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 33.013015 20.550300 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 33.370177 20.550300 translate 0.035278 -0.035278 scale start_ol 5568 2880 moveto 5568 2112 lineto 512 2112 lineto 512 2880 lineto 5568 2880 lineto 5568 5056 moveto 5568 4288 lineto 512 4288 lineto 512 5056 lineto 5568 5056 lineto end_ol grestore gsave 34.184416 20.550300 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 2151 -128 1991 -60 conicto 1832 7 1717 124 conicto 1603 242 1537 398 conicto 1472 554 1472 736 conicto 1472 913 1537 1071 conicto 1603 1230 1717 1347 conicto 1832 1465 1991 1532 conicto 2151 1600 2333 1600 conicto 2516 1600 2672 1532 conicto 2829 1465 2946 1347 conicto 3064 1230 3132 1071 conicto 3200 913 3200 736 conicto 3200 554 3132 398 conicto 3064 242 2946 124 conicto 2829 7 2672 -60 conicto 2516 -128 2333 -128 conicto 2624 2048 moveto 2048 2048 lineto 1747 3712 lineto 2258 3846 lineto 2462 3899 2645 3987 conicto 2828 4075 2965 4235 conicto 3103 4396 3183 4644 conicto 3264 4893 3264 5267 conicto 3264 5641 3198 5905 conicto 3133 6170 2994 6338 conicto 2856 6506 2644 6581 conicto 2432 6656 2132 6656 conicto 1871 6656 1672 6591 conicto 1474 6526 1322 6428 conicto 1088 5376 lineto 640 5376 lineto 640 6940 lineto 1052 7046 1466 7107 conicto 1881 7168 2372 7168 conicto 3576 7168 4188 6701 conicto 4800 6234 4800 5294 conicto 4800 4941 4704 4619 conicto 4609 4297 4413 4033 conicto 4218 3769 3921 3571 conicto 3625 3373 3228 3263 conicto 2767 3136 lineto 2624 2048 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 0.000000 0.000000 srgb n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse f n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse f n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 19.453100 20.599700 0.212500 0.212500 0 360 ellipse f n 19.453100 20.599700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 19.453100 20.599700 0.212500 0.212500 0 360 ellipse cp s gsave 14.655400 29.924000 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 21.205600 31.735200 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 18.162800 21.847900 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 15.467900 30.119000 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 22.030600 32.060200 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 18.937800 22.122900 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 1.000000 srgb n 18.749983 35.522480 25.200398 25.200398 302.711473 337.775677 ellipse s 0.100000 slw [] 0 sd 0 slj 0 slc n 41.703272 25.722318 m 42.120532 26.094331 l 42.167787 25.537315 l s gsave 38.096100 18.313900 translate 0.035278 -0.035278 scale start_ol 2752 3008 moveto 2752 512 lineto 3660 374 lineto 3660 0 lineto 249 0 lineto 249 374 lineto 1088 512 lineto 1088 6592 lineto 180 6726 lineto 180 7104 lineto 3559 7104 lineto 4444 7104 5039 6958 conicto 5634 6813 5992 6550 conicto 6350 6288 6503 5922 conicto 6656 5557 6656 5117 conicto 6656 4783 6582 4481 conicto 6508 4179 6342 3924 conicto 6176 3670 5905 3474 conicto 5634 3278 5233 3156 conicto 7113 512 lineto 7872 374 lineto 7872 0 lineto 5580 0 lineto 3599 3008 lineto 2752 3008 lineto 4992 5107 moveto 4992 5532 4908 5806 conicto 4825 6081 4642 6240 conicto 4459 6400 4172 6464 conicto 3885 6528 3483 6528 conicto 2752 6528 lineto 2752 3584 lineto 3509 3584 lineto 3922 3584 4206 3669 conicto 4491 3754 4666 3938 conicto 4841 4122 4916 4409 conicto 4992 4697 4992 5107 conicto end_ol grestore gsave 39.127636 18.313900 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 39.484799 18.313900 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 39.841961 18.313900 translate 0.035278 -0.035278 scale start_ol 5568 2880 moveto 5568 2112 lineto 512 2112 lineto 512 2880 lineto 5568 2880 lineto 5568 5056 moveto 5568 4288 lineto 512 4288 lineto 512 5056 lineto 5568 5056 lineto end_ol grestore gsave 40.656200 18.313900 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 2151 -128 1991 -60 conicto 1832 7 1717 124 conicto 1603 242 1537 398 conicto 1472 554 1472 736 conicto 1472 913 1537 1071 conicto 1603 1230 1717 1347 conicto 1832 1465 1991 1532 conicto 2151 1600 2333 1600 conicto 2516 1600 2672 1532 conicto 2829 1465 2946 1347 conicto 3064 1230 3132 1071 conicto 3200 913 3200 736 conicto 3200 554 3132 398 conicto 3064 242 2946 124 conicto 2829 7 2672 -60 conicto 2516 -128 2333 -128 conicto 2624 2048 moveto 2048 2048 lineto 1747 3712 lineto 2258 3846 lineto 2462 3899 2645 3987 conicto 2828 4075 2965 4235 conicto 3103 4396 3183 4644 conicto 3264 4893 3264 5267 conicto 3264 5641 3198 5905 conicto 3133 6170 2994 6338 conicto 2856 6506 2644 6581 conicto 2432 6656 2132 6656 conicto 1871 6656 1672 6591 conicto 1474 6526 1322 6428 conicto 1088 5376 lineto 640 5376 lineto 640 6940 lineto 1052 7046 1466 7107 conicto 1881 7168 2372 7168 conicto 3576 7168 4188 6701 conicto 4800 6234 4800 5294 conicto 4800 4941 4704 4619 conicto 4609 4297 4413 4033 conicto 4218 3769 3921 3571 conicto 3625 3373 3228 3263 conicto 2767 3136 lineto 2624 2048 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 31.055400 13.988800 m 22.759874 30.162670 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 31.055400 13.988800 m 16.092029 28.341885 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 31.005400 14.013800 m 19.680141 20.470265 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 31.005400 13.988800 m 23.524662 18.253064 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.738107 17.843629 m 23.427531 18.308432 l 23.985720 18.278011 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.055400 13.988800 m 25.191160 19.658377 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.296481 19.208817 m 25.110780 19.736088 l 25.644018 19.568286 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.030400 14.063800 m 27.681868 20.639541 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 27.635244 20.180168 m 27.631134 20.739170 l 28.080802 20.407057 l s gsave 23.530400 19.563800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 25.530400 20.838800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 28.180400 21.838800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 25.880400 21.113800 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 28.605400 22.113800 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 23.930400 19.813800 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 34.175200 22.592500 translate 0.035278 -0.035278 scale start_ol 3608 448 moveto 3662 448 3705 465 conicto 3748 482 3802 537 conicto 3856 593 3910 661 conicto 3964 729 4088 886 conicto 4213 1043 4342 1200 conicto 4494 1112 lineto 4029 384 3759 128 conicto 3489 -128 3176 -128 conicto 2917 -128 2787 25 conicto 2657 178 2549 604 conicto 2225 1916 lineto 1264 572 913 222 conicto 562 -128 248 -128 conicto 0 -128 -146 -3 conicto -292 121 -292 326 conicto -292 489 -184 596 conicto -76 704 76 704 conicto 205 704 410 593 conicto 616 483 702 483 conicto 886 483 1253 1015 conicto 2139 2313 lineto 1826 3657 lineto 1718 4149 1631 4280 conicto 1545 4411 1339 4411 conicto 1231 4411 735 4295 conicto 691 4453 lineto 810 4495 lineto 1761 4800 2074 4800 conicto 2290 4800 2403 4601 conicto 2517 4402 2636 3853 conicto 2755 3261 lineto 3316 4122 3672 4461 conicto 4029 4800 4386 4800 conicto 4580 4800 4704 4689 conicto 4828 4579 4828 4411 conicto 4828 4243 4725 4137 conicto 4623 4032 4450 4032 conicto 4342 4032 4169 4121 conicto 3997 4211 3900 4211 conicto 3586 4211 2841 2886 conicto 2841 2631 3273 902 conicto 3381 448 3608 448 conicto end_ol grestore gsave 34.122100 32.035100 translate 0.035278 -0.035278 scale start_ol 1615 -1472 moveto 1920 -1472 2256 -801 conicto 2592 -131 2592 183 conicto 2592 323 2115 1276 conicto 682 4348 lineto 552 4629 128 4694 conicto 128 4864 lineto 2368 4864 lineto 2368 4682 lineto 2021 4682 1879 4617 conicto 1738 4552 1738 4400 conicto 1738 4238 1846 3988 conicto 3083 1246 lineto 4128 4228 lineto 4171 4326 4171 4411 conicto 4171 4682 3648 4682 conicto 3648 4864 lineto 5120 4864 lineto 5120 4682 lineto 4926 4660 4812 4557 conicto 4698 4455 4600 4196 conicto 2933 -208 lineto 2500 -1374 2072 -1871 conicto 1645 -2368 1103 -2368 conicto 757 -2368 529 -2192 conicto 302 -2016 302 -1749 conicto 302 -1557 443 -1418 conicto 584 -1280 769 -1280 conicto 1007 -1280 1278 -1376 conicto 1550 -1472 1615 -1472 conicto end_ol grestore gsave 43.067000 18.175800 translate 0.035278 -0.035278 scale start_ol 2906 -896 moveto 2484 -896 1712 -429 conicto 940 37 573 37 conicto 313 37 76 -158 conicto -22 -61 lineto 3327 3968 lineto 1750 3968 lineto 1372 3968 1210 3849 conicto 1048 3730 875 3329 conicto 702 3372 lineto 1037 4608 lineto 4105 4608 lineto 4105 4491 lineto 972 774 lineto 1458 666 1787 416 conicto 2117 167 2246 -66 conicto 2376 -299 2576 -483 conicto 2776 -667 3035 -667 conicto 3327 -667 3327 -505 conicto 3327 -461 3251 -298 conicto 3176 -136 3176 -17 conicto 3176 135 3278 227 conicto 3381 319 3543 319 conicto 3716 319 3818 211 conicto 3921 103 3921 -71 conicto 3921 -397 3613 -646 conicto 3305 -896 2906 -896 conicto end_ol grestore gsave 43.000000 28.000000 translate 0.035278 -0.035278 scale start_ol 551 4418 moveto 497 4418 459 4412 conicto 421 4407 389 4407 conicto 173 4407 lineto 173 4549 lineto 432 4592 454 4592 conicto 745 4634 950 4675 conicto 1156 4717 1237 4743 conicto 1318 4769 1382 4784 conicto 1447 4800 1512 4800 conicto 1707 4800 1863 3496 conicto 2020 2193 2052 1377 conicto 4126 4691 lineto 4191 4800 4266 4800 conicto 4342 4800 4353 4647 conicto 4699 811 lineto 5757 2137 6119 2713 conicto 6481 3289 6481 3637 conicto 6481 3800 6249 4028 conicto 6017 4257 6017 4431 conicto 6017 4800 6438 4800 conicto 6676 4800 6838 4642 conicto 7000 4484 7000 4234 conicto 7000 3712 6330 2614 conicto 5660 1516 4963 662 conicto 4267 -192 4126 -192 conicto 4072 -192 4045 -137 conicto 4018 -83 4008 135 conicto 3694 3611 lineto 2733 1912 lineto 2549 1584 2349 1202 conicto 2150 821 2031 603 conicto 1912 386 1798 184 conicto 1685 -18 1598 -105 conicto 1512 -192 1447 -192 conicto 1372 -192 1350 -94 conicto 1329 4 1307 321 conicto 1264 1279 lineto 1210 2794 972 3916 conicto 918 4200 831 4309 conicto 745 4418 551 4418 conicto end_ol grestore 0.117647 0.878431 1.000000 srgb gsave 32.800000 20.750000 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 39.250000 18.500000 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 31.350000 13.500000 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.098600 14.065700 m 30.261166 10.950216 l s [] 0 sd 0 slj 0 slc n 30.163822 10.588071 m 30.535044 11.006035 l 30.261166 10.950216 l 30.052184 11.135827 l ef n 30.163822 10.588071 m 30.535044 11.006035 l 30.261166 10.950216 l 30.052184 11.135827 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.060100 13.988600 m 28.061745 14.754865 l s [] 0 sd 0 slj 0 slc n 27.698422 14.847717 m 28.120952 14.481700 l 28.061745 14.754865 l 28.244754 14.966130 l ef n 27.698422 14.847717 m 28.120952 14.481700 l 28.061745 14.754865 l 28.244754 14.966130 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.098600 14.027200 m 30.804078 16.743334 l s [] 0 sd 0 slj 0 slc n 30.763653 17.116148 m 30.569011 16.592111 l 30.804078 16.743334 l 31.066097 16.646013 l ef n 30.763653 17.116148 m 30.569011 16.592111 l 30.804078 16.743334 l 31.066097 16.646013 l cp s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 31.066100 14.016400 m 22.853207 14.261918 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.233760 14.000430 m 22.741453 14.265259 l 23.248700 14.500207 l s showpage opengv/doc/addons/images/point_cloud.eps0000664016516101651610000005770313344612246017335 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/point_cloud.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 12:08:58 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 638 717 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -9.888385 -31.647700 translate %%EndProlog 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 0.000000 0.000000 srgb n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse f n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse f n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 19.603100 18.049700 0.212500 0.212500 0 360 ellipse f n 19.603100 18.049700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 19.603100 18.049700 0.212500 0.212500 0 360 ellipse cp s gsave 16.205400 29.774000 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 23.205600 31.135200 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 17.017900 29.969000 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 24.030600 31.460200 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 1.000000 srgb n 16.144970 36.373257 27.246708 27.246708 268.639210 301.183774 ellipse s 0.100000 slw [] 0 sd 0 slj 0 slc n 15.877903 8.871040 m 15.386146 9.136888 l 15.893879 9.370784 l s gsave 20.878100 8.878440 translate 0.035278 -0.035278 scale start_ol 2752 3008 moveto 2752 512 lineto 3660 374 lineto 3660 0 lineto 249 0 lineto 249 374 lineto 1088 512 lineto 1088 6592 lineto 180 6726 lineto 180 7104 lineto 3559 7104 lineto 4444 7104 5039 6958 conicto 5634 6813 5992 6550 conicto 6350 6288 6503 5922 conicto 6656 5557 6656 5117 conicto 6656 4783 6582 4481 conicto 6508 4179 6342 3924 conicto 6176 3670 5905 3474 conicto 5634 3278 5233 3156 conicto 7113 512 lineto 7872 374 lineto 7872 0 lineto 5580 0 lineto 3599 3008 lineto 2752 3008 lineto 4992 5107 moveto 4992 5532 4908 5806 conicto 4825 6081 4642 6240 conicto 4459 6400 4172 6464 conicto 3885 6528 3483 6528 conicto 2752 6528 lineto 2752 3584 lineto 3509 3584 lineto 3922 3584 4206 3669 conicto 4491 3754 4666 3938 conicto 4841 4122 4916 4409 conicto 4992 4697 4992 5107 conicto end_ol grestore gsave 21.909636 8.878440 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 22.266799 8.878440 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 22.623961 8.878440 translate 0.035278 -0.035278 scale start_ol 5568 2880 moveto 5568 2112 lineto 512 2112 lineto 512 2880 lineto 5568 2880 lineto 5568 5056 moveto 5568 4288 lineto 512 4288 lineto 512 5056 lineto 5568 5056 lineto end_ol grestore gsave 23.438200 8.878440 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 2151 -128 1991 -60 conicto 1832 7 1717 124 conicto 1603 242 1537 398 conicto 1472 554 1472 736 conicto 1472 913 1537 1071 conicto 1603 1230 1717 1347 conicto 1832 1465 1991 1532 conicto 2151 1600 2333 1600 conicto 2516 1600 2672 1532 conicto 2829 1465 2946 1347 conicto 3064 1230 3132 1071 conicto 3200 913 3200 736 conicto 3200 554 3132 398 conicto 3064 242 2946 124 conicto 2829 7 2672 -60 conicto 2516 -128 2333 -128 conicto 2624 2048 moveto 2048 2048 lineto 1747 3712 lineto 2258 3846 lineto 2462 3899 2645 3987 conicto 2828 4075 2965 4235 conicto 3103 4396 3183 4644 conicto 3264 4893 3264 5267 conicto 3264 5641 3198 5905 conicto 3133 6170 2994 6338 conicto 2856 6506 2644 6581 conicto 2432 6656 2132 6656 conicto 1871 6656 1672 6591 conicto 1474 6526 1322 6428 conicto 1088 5376 lineto 640 5376 lineto 640 6940 lineto 1052 7046 1466 7107 conicto 1881 7168 2372 7168 conicto 3576 7168 4188 6701 conicto 4800 6234 4800 5294 conicto 4800 4941 4704 4619 conicto 4609 4297 4413 4033 conicto 4218 3769 3921 3571 conicto 3625 3373 3228 3263 conicto 2767 3136 lineto 2624 2048 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 31.055400 13.988800 m 22.982037 29.729517 l s [] 0 sd 0 slj 0 slc n 22.810898 30.063189 m 22.816636 29.504201 l 22.982037 29.729517 l 23.261531 29.732386 l ef n 22.810898 30.063189 m 22.816636 29.504201 l 22.982037 29.729517 l 23.261531 29.732386 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.055400 13.988800 m 16.443340 28.004902 l s [] 0 sd 0 slj 0 slc n 16.172714 28.264490 m 16.360490 27.737954 l 16.443340 28.004902 l 16.706608 28.098790 l ef n 16.172714 28.264490 m 16.360490 27.737954 l 16.443340 28.004902 l 16.706608 28.098790 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.005400 14.013800 m 20.308368 17.800067 l s [] 0 sd 0 slj 0 slc n 19.954859 17.925193 m 20.342787 17.522686 l 20.308368 17.800067 l 20.509622 17.994031 l ef n 19.954859 17.925193 m 20.342787 17.522686 l 20.308368 17.800067 l 20.509622 17.994031 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.678431 0.678431 0.678431 srgb n 12.847500 23.762500 0.212500 0.212500 0 360 ellipse f n 12.847500 23.762500 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 12.847500 23.762500 0.212500 0.212500 0 360 ellipse cp s 0.000000 0.000000 0.000000 srgb gsave 18.885800 19.165300 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 19.698300 19.360300 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 11.550000 9.150000 m 19.068799 17.684431 l s [] 0 sd 0 slj 0 slc n 19.316692 17.965809 m 18.798582 17.755900 l 19.068799 17.684431 l 19.173754 17.425376 l ef n 19.316692 17.965809 m 18.798582 17.755900 l 19.068799 17.684431 l 19.173754 17.425376 l cp s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 11.600000 9.150000 m 12.805485 23.065013 l s [] 0 sd 0 slj 0 slc n 12.837850 23.438614 m 12.545629 22.962057 l 12.805485 23.065013 l 13.043763 22.918902 l ef n 12.837850 23.438614 m 12.545629 22.962057 l 12.805485 23.065013 l 13.043763 22.918902 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.550000 9.100000 m 22.413575 29.752665 l s [] 0 sd 0 slj 0 slc n 22.588151 30.084551 m 22.134126 29.758421 l 22.413575 29.752665 l 22.576640 29.525652 l ef n 22.588151 30.084551 m 22.134126 29.758421 l 22.413575 29.752665 l 22.576640 29.525652 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.600000 9.150000 m 15.796236 27.835826 l s [] 0 sd 0 slj 0 slc n 15.878403 28.201713 m 15.524922 27.768641 l 15.796236 27.835826 l 16.012772 27.659086 l ef n 15.878403 28.201713 m 15.524922 27.768641 l 15.796236 27.835826 l 16.012772 27.659086 l cp s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 31.000000 14.100000 m 13.488591 23.531660 l s [] 0 sd 0 slj 0 slc n 13.158434 23.709483 m 13.480095 23.252281 l 13.488591 23.531660 l 13.717193 23.692491 l ef n 13.158434 23.709483 m 13.480095 23.252281 l 13.488591 23.531660 l 13.717193 23.692491 l cp s 0.000000 0.000000 0.000000 srgb gsave 10.396600 9.752030 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore gsave 31.452300 14.099700 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore gsave 32.086705 14.099700 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 21.982000 9.114540 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore gsave 22.366638 9.114540 translate 0.035278 -0.035278 scale start_ol 863 2752 moveto 948 3797 1000 3999 conicto 1138 4326 1367 4352 conicto 1452 4352 1514 4296 conicto 1576 4241 1576 4163 conicto 1576 3999 1000 2752 conicto 863 2752 lineto end_ol grestore gsave 21.982000 8.164540 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 31.042600 14.069300 m 30.205166 10.953816 l s [] 0 sd 0 slj 0 slc n 30.107822 10.591671 m 30.479044 11.009635 l 30.205166 10.953816 l 29.996184 11.139427 l ef n 30.107822 10.591671 m 30.479044 11.009635 l 30.205166 10.953816 l 29.996184 11.139427 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.004100 13.992200 m 28.005745 14.758465 l s [] 0 sd 0 slj 0 slc n 27.642422 14.851317 m 28.064952 14.485300 l 28.005745 14.758465 l 28.188754 14.969730 l ef n 27.642422 14.851317 m 28.064952 14.485300 l 28.005745 14.758465 l 28.188754 14.969730 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.042600 14.030800 m 30.748078 16.746934 l s [] 0 sd 0 slj 0 slc n 30.707653 17.119748 m 30.513011 16.595711 l 30.748078 16.746934 l 31.010097 16.649613 l ef n 30.707653 17.119748 m 30.513011 16.595711 l 30.748078 16.746934 l 31.010097 16.649613 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.531800 9.101540 m 11.237279 11.817634 l s [] 0 sd 0 slj 0 slc n 11.196853 12.190448 m 11.002212 11.666411 l 11.237279 11.817634 l 11.499298 11.720313 l ef n 11.196853 12.190448 m 11.002212 11.666411 l 11.237279 11.817634 l 11.499298 11.720313 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.578400 9.108040 m 14.063630 9.015972 l s [] 0 sd 0 slj 0 slc n 14.438373 9.002089 m 13.947971 9.270428 l 14.063630 9.015972 l 13.929461 8.770771 l ef n 14.438373 9.002089 m 13.947971 9.270428 l 14.063630 9.015972 l 13.929461 8.770771 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.558900 9.106390 m 10.208691 6.866437 l s [] 0 sd 0 slj 0 slc n 10.015098 6.545273 m 10.487332 6.844430 l 10.208691 6.866437 l 10.059113 7.102554 l ef n 10.015098 6.545273 m 10.487332 6.844430 l 10.208691 6.866437 l 10.059113 7.102554 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.117647 0.878431 1.000000 srgb n 11.564700 9.147620 m 30.813873 13.885359 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 30.377177 14.035338 m 30.922437 13.912080 l 30.496675 13.549827 l s gsave 19.557000 13.323000 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 1934 -128 1649 -32 conicto 1364 63 1183 230 conicto 1002 398 917 628 conicto 832 859 832 1130 conicto 832 4416 lineto 182 4416 lineto 182 4776 lineto 948 4992 lineto 1570 6144 lineto 2368 6144 lineto 2368 4992 lineto 3414 4992 lineto 3414 4416 lineto 2368 4416 lineto 2368 1211 lineto 2368 864 2512 688 conicto 2656 512 2891 512 conicto 3072 512 3250 538 conicto 3429 565 3584 597 conicto 3584 163 lineto 3509 110 3365 57 conicto 3222 4 3049 -35 conicto 2876 -75 2687 -101 conicto 2498 -128 2333 -128 conicto end_ol grestore gsave 20.034052 13.323000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 20.391215 13.323000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 20.748377 13.323000 translate 0.035278 -0.035278 scale start_ol 5568 2880 moveto 5568 2112 lineto 512 2112 lineto 512 2880 lineto 5568 2880 lineto 5568 5056 moveto 5568 4288 lineto 512 4288 lineto 512 5056 lineto 5568 5056 lineto end_ol grestore gsave 21.562616 13.323000 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 2151 -128 1991 -60 conicto 1832 7 1717 124 conicto 1603 242 1537 398 conicto 1472 554 1472 736 conicto 1472 913 1537 1071 conicto 1603 1230 1717 1347 conicto 1832 1465 1991 1532 conicto 2151 1600 2333 1600 conicto 2516 1600 2672 1532 conicto 2829 1465 2946 1347 conicto 3064 1230 3132 1071 conicto 3200 913 3200 736 conicto 3200 554 3132 398 conicto 3064 242 2946 124 conicto 2829 7 2672 -60 conicto 2516 -128 2333 -128 conicto 2624 2048 moveto 2048 2048 lineto 1747 3712 lineto 2258 3846 lineto 2462 3899 2645 3987 conicto 2828 4075 2965 4235 conicto 3103 4396 3183 4644 conicto 3264 4893 3264 5267 conicto 3264 5641 3198 5905 conicto 3133 6170 2994 6338 conicto 2856 6506 2644 6581 conicto 2432 6656 2132 6656 conicto 1871 6656 1672 6591 conicto 1474 6526 1322 6428 conicto 1088 5376 lineto 640 5376 lineto 640 6940 lineto 1052 7046 1466 7107 conicto 1881 7168 2372 7168 conicto 3576 7168 4188 6701 conicto 4800 6234 4800 5294 conicto 4800 4941 4704 4619 conicto 4609 4297 4413 4033 conicto 4218 3769 3921 3571 conicto 3625 3373 3228 3263 conicto 2767 3136 lineto 2624 2048 lineto end_ol grestore gsave 20.178200 13.522700 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore gsave 20.562838 13.522700 translate 0.035278 -0.035278 scale start_ol 863 2752 moveto 948 3797 1000 3999 conicto 1138 4326 1367 4352 conicto 1452 4352 1514 4296 conicto 1576 4241 1576 4163 conicto 1576 3999 1000 2752 conicto 863 2752 lineto end_ol grestore gsave 20.163500 12.711900 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore showpage opengv/doc/addons/images/relative_noncentral.dia0000664016516101651610000001357113344612246021015 0ustar dimadima‹í]Ms7’½ûW0èÃ\d‰L|äôÈŽGÌ\»3Þ3£I©^7»ͦdÍa~û"QMJ"Q"Y](±Ú ÂŽh¬Šù‰üøËO¿_-Þ7›ëÅzõæ”>>jVgëóÅêòÍñÿþú·ÂñO?~÷—óÅüÏñ¿ËÍüê(þÆêZ>½9~»Ý¾ûóë×>|PË×óíz£–‹uݼþÏ|¹œ¿Žƒ^ÿøÝÑÑç8Ÿoçò½ÝwçÛífqz³mŽVó«æÍñéüì·ËÍúfu~ÜŽÚ;[/×›£÷óå›ãï/Ò×ñëÝc^ñœ¯<ûÝü²9Ý4óߺ­ãsŸG¿k6÷{õn}½ˆC¶ß=Òñùÿgcv£®ã ÕåßÿÒl·ÍæûvZ»o~z^n²‚¶WóÍåbõPV|?Ëöee‘åËA°¨ÇÛ÷ò|q§ãŠ[Ž+n3®¸ÅõÉ»õf»™/¶Ež®×Ëf¾j¥n77M9×góeT±¯- ú?ýb±Ý®™ÿÅ|yý”´ß¾CÜsÑ{¹Yœ¼_ŒèxʇÅùöíÉï…^Wûô…žþ~q½8]6¹Ù/VÛÁÿq˜Çßÿë$ÿôë{jCû´Î-â<4¶±Ïß".oçÍõ#jö嘎'½Ý {ýØ[¿?î©/¦ýÖ½ ;‰XÎ?6›Ýãÿúi«>ÚýwŒs4?Û.Þß~úì¬Oÿ¯9Ûîû¯í|u>ßœýpôËbëΉfÈâüÍñÿè/ßÖýõŧE"|ðºÞ­ïtÊX…dü+°Š"çÞy¤KÌéé})›¸ùêrÙÜI2žI$!2Î +í¿2.΀{J>[¯V'Íê<­¨×:3CãÄ4Z™˜ ŽúMlusuöîþ|rH~ÎCã^Óœ\o?.›ûOn¢¼öÑOœ¯¼¸ø÷‰Êtý€:nrô6ªŸ¨,m×QÛèøèÓO߇‡¸¹÷ÐöÛ­N÷WrØ[ÉYax^E•œ‘ä-ÏÐ(2^¡VØ”Öñ®e>'†ÎBš˜a[uüNÇÑVò_›ß·Ÿ)9ì”Üì«ä¤U0!þõƒ2‘¿ *ù$•ÇâŒ@¡v(’-ô•¼•×òˆsoL—QžŽ}_Œ»wJÜv¿bUu™èëÕ6'I¾t1¿Z,?¾9þuqÕ\ýwóáèŸë«ùêø(©wT­HpícÒˆþº^žÚçOçm³¸|›Ðg6°ò!þó>2’Còšö“ù¥V>K3ûˆûÒöìtRœŸ]À~‚âÉîruÕäÿ¾Ÿ¸H?QJÖ²|DÞ§)uÓâcÈ{ Qý½Y_5ñ·Î"Sý£Ù\ÈO~^lΖM†³p_ΠœÅW¢ÅÅ¡ e‰ ÅíÎr˜!+0AäR žrãkš?FX狳m¿§7Ëæêäl½Y=ôˆ üþ’¤tv~øo9C‹ß¾<¸=„=`©RÒ’-ñèÒ@·_@¬˜=„ ÝlªÅ'jšŸË¿~".Ëea×o×N2.æÇ}gCyúýšõã<ëý-ïNÞ®7‹Çíy¾üêâî9Öž-&’åvqVNÈõÍ©x›ãÞ/iðí€ö>§|<.‰KÀ.yN‹’L+ÉxÃâŒ@âôÙ³çéº%Ô-¡n uKèéʰøëœ¶ôÊxå<•u×µ‚"[2Ï0ÒŒÖI.zù~ŒwÕ1¦£K-‹¹1î³vuc GRnoßE$ „xø6ÊXgJ:/n%É-˜Y<õ{ã’dëúJ®O­*OÊS]šY‰ê%ÕmÎ2Ád¼7O¡òV¢]P¹EÏ}QBÔp‘„Àvf)î“)Œ"x‹…ƒÉ:—ùp¨ÌK{—&ÔÓœoÎNîc#›|ò)¯å™+¿Ù¼oNÎ×ñŸ}ÅGúÄSµ €È¸&sÕ0LØÜÃýh¾ÙžÌ7›õ‡îgÃÞÏ>Y6«Ë¯¿+»¿Gÿvk öÜ&+F ¼RÚaÉcݤhä9’dônnòþÁÝOŒ÷àÈ0– ЇûuifÁp¿/·…j. |ƒ¤˜è?¸h”_J1ñ»G3ãT°>Jfq”ã)&¹uf†ºx¢F&FN¿¸“Gí°‹ \ÏxÕy!câîÉåL‰O"^Š!a€'H(”XïÁ¹²ðl%y9G»Yüì´GA°›€ßå¢ÞczßÞ¥™Å ‰û¼V ‰™ `*'±Â 3U+)( bHÀŽ©êMVõ?M3+SMñȳw ;‚26€ËF°[#þY£‘gQ$‚Þº5”ö?X`6ÝËô^Òñ¦>Š(P(¨U4XE™|‰µÞHò29ðåqád‡%§ÐV¤*RÜHA›øž= ãŠö“Ô†P!3RÄÂûÝÎBfÀd—™­aáe’\as°°ñCÀF%}2¶0j¨œÙxb´åD8à¨É­2sWï”¶2+?9§óý¢–ß –avŸ¤ôBÂbÃÏ€3â}f á~R¯)k²“Ãâ\}Q/€^y g°¸9zæv’DK«4+þUîq;ì!Œâñ0¤V Úü¡Y0v¬b}Ðqû—ûtʉê$A½B¹•dkëfÆ+ÔRœ±žÀeïûzÙ;êeo—f– ²¿G™õ e@¦Ú?jÌKõݤ6òGI¦º•„Ê#‚0•‡˜Ê1ÖËÞzÙûDͬL5E¦2CT-C9:Xq,.Z–EbòNj–YkS^ã TÕ z’ZV–š"Ká5ðƒ¨ƒTêÒÁz‚›`¹Ù;&[ÒtR(\I#ÉRTs—J8°!%.iâÔ“©tšDç:³UFÁÅ3„L¬wïšó÷âpï gksJ½ó„%]´"]:b#vX“OIÚ•N•íZfe>Í+j50Ä–Ðæ†BÑTY‹Jïª)92 6:@ÜrPaùÂÖëÌ õÁÈÄL\“‚jRÐËK ½X­‰ÛCHýÅŠvº•$n8mpÆ ‚âËÒSèdöþO5ˆuÌ‹ƒNÕ¬ÑaôÒáÞQ¬Ö« ‰ÃqG¦¢Ñw‚ŒÒlhfƒb¯öÜ·”teªfªͬD5E¢Ú;Œ5ò¹V<– d½d[i‰JƒÈeàm_£íŸ¦—•¦¦HSv§Kí1J2T’”“è)ª{ò¾0Ö‹ÏÖ¥†52ìÅÒß›õUë,2Ò?šÍ…üäçÅælÙä¸iÿ(Võ@Ú#qÑÚQ¶’ G ½4NOŸƒ¡ž’㫚?FS狳mO7ä²¹:9[oVͦô+L¢uv’!þôåû¶gHÂT)iã·h&ºùªÓ¾±ò¯Ÿˆ‹ÅrYXÄõÛõ‡“ÓùÙo—›õÍêü¾˜ÓõzÙÌW­ íæ¦)wû \Ý|¶…õ|ËÅ»“·ëÍâßqOž/¿º¸‹ùòºÙCLdÌí⬜ë›Óëøø¯t:…Ñ÷„ýËùe4‡W¨{,™Æ%ÝI2˜ª`»@ñ3(¢¾% _Äž0Ä+¬{¨{Âý~àö„}DÔ=¡î Ïs\ R@ZzÃE6‹lÊÖ®m%IýhHu¤8Iöì&âö®^šëÖ¥™å\¬÷¨»z4dª!Êksð˜ø"@a¦º•¤5£˜¬´c*vSð¶Ö» Qï‚:5³2Õ“NHaSp*"ÎîBÛ›Ã:1©ÀH%ãxŒ–lÙUfÛzšÈœ2/ÒÆ×.5H·/8apa«¶Œ¥›u8’šÆ;C ZtIrðc4€Ë®3{»¡À÷͊ΊΞF>íB¨@ F$k’K¦ÞIÒÊò³ø9h»5ê¾’kèÃuGtiføš ;‚p¦ò;}‘?Ê2Õ­$m™!)@RÐPƒ™@²Ïªº#FuGtifeª)º#ö¡—–|ÚØýZò=©H2©ús iO賡6å|ñV¡]ëÌžxMÏ¥ýÛ†îqÉ<`B²üi¢D}½~0ÙÛŸ½.ô·Þíº h<úôc‰Ë½'ëÁSÒÞAÞ(e*(¨hëx«‚ß(L˜a”E)Ù¢±o'­§ã¨k™™¡AyÖ,i¥ìõ‹Kìÿ–Zþ”Ü Qô%¸]Y‡P¸ê ²¦ä¡²mÕm!•³ðp„ª/Ùuf‡:†T2U÷uuõ>vúRÚS®lªQ’b¥¸"Íl4“"$S“Àµ¼DuŽ=E+ëqsŠŽ±0C…VØN‡Üɹ]³’kÔVgƒÞe·ªWìp¶ójYIjŠ$ÅCÎ7‰,l(\9¿Uº •ó ´¨6ô¨•ª»õ°–Ο )Y=@é|#Š WÏObŒrVêçk× í[±°²ÒÖÏÏ(b-¡?ÁëC 8„Ô‹Šö‹.š*ÌJ“iý¬dÍ,Jöra@AïâýÏqç×™¹ö`:´3õÚã[_{Øýk÷¢d›¥zo¦èî‹>*³%‚”î…t·M@k‹+yÇ23:îãçd^Ä„õŠüpEnq€rh£zYñ²`Ù²Îh+’‚s(õÐH3Kv1D3©4Œ:–™­á<Û4/ÄzCþ™’ûo¤äû×$•vw¢{ ¡Kj¹ae‘d‚Ž( "Ù)‹ŽJky×:3^‡ÈD"ßwb©æô´|ïh§ø'%Üù+µ+¬åè½KFÉÑ u” ”ôŽuéD©ÎufÛïláÓË”º¸ø²dc ùVyŒÖ Õ¼m[€”ê…VëSPo´¸8)”½›ù<'¨7¿ÌlÜ¢×”&&›å µËÐT€ï‡ŒBŽG‹q¢Q[/å\˜$,L›@#†!±Î|8)³šMÝ—+<ûÃ3 q8 žÛCSÑ2EÍeg¡µFM{8$Ÿ:X 9?Âá0»ÎÌuR´¬=™qžž}áÉC8(I2VâîÖ—m-¸ÉCim=”ÒQÆ©@ÞŽà¡Ì®3Û:Úñ(sh¹Â³Â³'<žÌ5qÜ<5ï®áÜî.nž¤ô˹†‹ó ©[»$ý{¨‡Úz¨}¸‡AZÍ;ßfã-ÝkÞ´=³]HmÞœ‡”ÁJàÇh5Ÿ[fvΤÔÚ`lí7¨Ð1ƒÄgÅKâ–ÐcÙ®Óm $Je&Ûø,íÅä„1â³rëÌv;6Ú§:˜ÎR¨m…gÏ n·(-*m…„¢·¨;A²µh@©‹lëšB£å‹š²;j=»½,å}ŸÔj”÷€4E”Å%p‰-,®Š›iE>¤. aGS„!ÔÚú5m÷IzYijŠ4µ .¯€$y-u…ãô“$PÖk'—ßÎ#KRؾ’«=u¸öT—fV¦š"S¹˜Ê“胸úua¦j%ɽ);¦B VB©&ÕÓ4³2Õ™jï€B ÉC”llW’¨n+f˜+pm4½õS0¨jQ¹Q-ª.½¬45Eš ÐTÀV,AYšjiå]°ÂSÆIÂC„€ ¨,ÕžµZJ‡bVžš"Oñ÷ñÖJ’Wl ×Ïn9å¤ZŠSd$Þ4Èýx5§ª9õ4½¬45Ašòz€2½²%#]M½ä…Ÿ¬ð”E"ÛzãWÍ©')få©)òÔþ‘ÁF9ò©-Z¶eÃuž¬¤ب÷"Ù¹)Uµ¨F¶¨ºT³RÕ©j‚ÜêCTÀ¢Tu+ %I@˜ÊÉÑ/ µ!hµ¨žª—•§¦ÈS8OÉÉKÜñ ey*I’l+­S–e$(lvÕ“^‰êiŠYŒ¨j—–r©mž¦–JmZ¨7©Xƒ5É·®¹x‘³ç¥…¢IE%˜©v¢¬‰m}Áip kÚ)­+ Nˆ:/mÅ#8Ù{ñ ´ui-pñ¼Ó®uæk"Ÿ²08¨ð¬ðì ϽããÖÉ&¢’a}†"@$Ûš”·ìfQ2™T%ÐBñ¬ðÎef†J[·ó’p-©p°ØñC`ÇQRa¢E¢NNÐÙ„é+rEÜÐÉ®2 ôdbdVè*t Ðá¤S¦h1’(È0§åQyÃ,žÔ N=¨ÁŽ‚Ì23#ÅX•¢¹Ó+t:¹, A=é,r`äõ‹R•¼ LÑ|ä€ñ‚b)”Õ};h>9™UfF9™!„ŠœCEŽ¢ÿŽs¾mLStÓATŽl2ϼÕ<‹’9y XYd3Bžì:3CQyjýôä+t:8tw*¥máÖU!A9Hï*HÕ¹÷…ò³ “]g¶ÙM@›,É`^ÔÅnÏ à¡!À#1T¢T½{?<Þúd59'àAö Lq8x²ëÌ‚Ç@Hµ¶î<‡ ;Dï4ÂzŠqðe{§9µW+Ðgè”q²@Ä»Z§e—™jd¢*v;nȾƒ…±C‘ÇCOÜo|²ÚX[‘ìz_*õê;øxRf˜Œ4†ªÑv°Ø¦gg«)¤‹6Œ’¢­–°•ØËÆ“båÀHùÒ1 “[fv¨sd^Ö‘©Ø9Tì„!ú›°X($M= wìCNð¨|l+¯½H&tf„þ&Ùuf;ö‘‘ ’”F¬ÏÁ‚‡´J W#2ÄBèlÛm— cüùùUæS-<›”äïl…ΡB‡õÐñZïøØPYèN‚€<ɶÃÖ¤îU¶wçžç`'¿Ì|)G)Z•¼­¾‚ƒÅ ÐÝjÛ&ÂPѸ‚(I³éâÄ{”&èÑfKíd4Bùèùef‡F²½y ¡†ä,vÌØ1DI©,™²Ø!Kms@;ñ,âyǘ¸i<Ùuf í³“‰i¯+x<8ÈÆ )•1%mV+oÚÎTÆÊÆc} .ž»Ó¹ÎÌÐø×ÓÔNÌÔÜà Q¿JÇC»t¥GÍ…KíYK")b¥. j ÒåÞ¢)n¶u­3»óo­LŒŒ©à9XðØÀ£rRª²ñ " Ñ¡f3³$ñ¡F$[7vòËÌz©-"µ0s5,ç`±ã†ÀN²¢¦]¸…=ÙöÄÎSåDØaÇ„â©oëÌn<ÖH_Üxä‰g² žCÏÞ±V²6RI¨Þ ÆOOPŒI!*ç̲ø¼Éb2¥£©;×™*ùoL2±àu .8Xð„!ÀC˜t \Qw‚‚OØ!'õå°…ÐÈÉ-23Ò+L¬"pjúÛÁ‡ÙuØ´Je¸ð®ÃÚÉÜ´ö“ä0 v²ëÌe- ˜H2å\Ï‹Oûy9ÿØl~ü®ýÿ»Ü̯~üîÿøÄ¤²–opengv/doc/addons/images/point_cloud.dia0000664016516101651610000000526113344612246017273 0ustar dimadima‹í]Ksã6¾Ï¯Pi¹xh¼q¬â2/¢4¹VæôqšÆ§ÐètúùÃdò¼ƒy\Æö½õ»qYÉåmi&Y¼4çÓËxöÇ¢Èo³ù´jµn7ËÓ¼˜ÜÅéùôã•{MO×Ýœ¾ègOß7ñÂ\&þ£¹k/­Ût}cŠín—7ù*&åÃÍN“†~ì¿ÏÚ¬[­ Q¶øüñS–¦øX kýæSuƒm*—q±H²],XŸ´Z qªíK`Å)"’nÖåx¸ËaáÒaáŠaá’ÕÅM^”Eœ”»—yžš8«PËâÖ´ÇYÍâDlß´pûÞ¯’²ÌŒÿ*NW¯™@õö£Æ«½‹"™ïWÞ-z¹OæåõÅ7OËUõþà©÷»d•\¦¦nôIVöÖýC?Ýo:ŽÁŸ~½£4T½5šˆ¹2ÜðãMÄâ6™›Õ1{Ù¦¡§ëu³ÓC«¾Ýîµ S½µe°D?˜bÝýO¦z²þ€×Œ3‰ger·yz¶&ùåïfV®'ûO“/  Î&Ÿ&ÿ1Å•ýÉOI1K¡ƒ'Ÿd:IæçÓ£— ·=Uè8qgånòGñ"$bDÊŠ"¬(ß^”]Ji‚¹¼ÜF)`äq¶HÍ#•k$JùAúëìû“«x™¤çÓ¯ÉÒ¬&ÿ2÷“_óeœM'N]ϧ M×ݸŸ~ÌÓùsM=~8;æ N–­åVRJ­´ L"Ö ó¥H#–mÐ^†¹_ÉÚm€â4YdKSÿñ6Pë¾ @]û8 ¹sCjfy:I±Î!mj¥AœPaÊ}:«$bTDγ4åk‹xêÝòT£d¢!QñÎÞx5XjKZhŸÞÔÖ‚[wŠñÊÂ\ð·ÏSømðÔMU?€§"”B5Ñ\SD¼ûS ‚hj„4%:ûSàÕеW#Wjƒ„"†ÙúSLPl‘“òíó <5$O5Jf ª·LTÿ(fÏx ­yJö·&’±prbÂoÞš`ÊNlšZqu|E1Õ'˜F˜°–ñ©Yže&›»µšçnSáÄ Á§ÝÀâbv±­µŠñT|~äÌo‹;s1OV°Æ³=AÒO°m"@+TK@£À5|,¹†ñó–Ÿ ,XQ^ÄE‘ß7÷;÷}‘šl±­xwƒŸÄ]RÝ%)©0üÇ|É7H2ˆ2fÝ%̹°Ä Z#é.ý:™œ !¨ACPMÒéÕezn‚ËÔ‚¬~#Rã3é®dž3âœYA+¥ü– çˆh‚ù™€’ªø›ˆ¶e¯ö˜gY[Ì-¹Ö.4&HË-'HÁìf{éƒ$#¥µ€„B™É¶È¡¦òýÖ~7If¨a±f=UZQ+T êwëZ!)pX¥:#öb“Š©8“êí3Uª•­ªl’ÌÀT#L½áîåßöƒ6Yïu7ÁmÒ¶XÁÎb‚qa£Tø.Uª™âž£Ñ*BL‡œ[ˆ®u‹®‘¡âì¢ 0g\[Ð৸˜ç؆£„ÀÌ?ˆÃ@"›».²‘ª¿ÇâÀÀ,}dð¶¨E-²7ï³s¡ˆEA”0i¯t”ØÕô(†r-Tó†H·«ƒgªy†V5ÏQçY "Üõ}ëu~ž·—Ìênñ%‰n›Jx=="‘HaBÎ(I¬9Ñ#¸«bö] (ÿÕ( ÆHP‹¨ Ž´"6n÷z8¼R¥dC³œ[\*[ãvzwè4Hc8 >Fr¢=‘“а„œdDÕšœ¨v§GÆAN›ã¦a Ü4Âj9Âú8’ÊHmÚgàÉÞæ¬@òllAr鎧#{»³õ½b€S©µó¬½Ý I¥ì@™¢o©n.‰ûÕÞËîõ1kM¼Þá)ÁŠÛó€D1«²B ´‡[aÅCœé®›g}‘§Ìe‘”ÔAyÞ­òˆ>Mõú…ˆÀè áꚤé!˜ØÃp”< éy1ÏZÓ#4wßfE( Úó~µ§—BDŠ• 2 ìuW ~ÒÛz$&³C³!z†‰  ±vžµM±bÊŒ¢¶çƒöŒ@{ú¨ããR¹Ë~‘BÌs5qùvÁ5íaö|€•gªHÛ:£´§vž5MYÄ9²WXj-5ÚónµG÷R¯´“*A}~ÅŠ‹Pu""Ê©”Îöé Ô%÷~•Uã“'cçN¸¸àÖ-XX”Þ©›6•™‰–-Á0HL„³3h\®Ac%‚¨î²eË A¼¨wo=Š„””`РÒ;ù|àñ`e77Œ‹øxøúB €¿¿ƒ%‚¨ ²ÍQû˜šâða|ú)–.}ù!‘ –ïÛ‡ÌLDGÀãÇ02‚•UÆIQid0™¨ËNŸ†»;œœ0nŽÃÞ½>ÜÐ1A¼™*EÔeýûÃÉ 4 • …Î`íZÄÄ:2‚ ˆÞ-Q_äçÃÊ QQhßb1žüü3>ú < ( ææ†Ž‰ ˆZ„ôn B,ÀÑ£X¾¾ÿÍšaÏCÇDD-BÒ-AèEaèPøú@r2d²Ò©U»w—îÃLDÃF“ ¢¤¥ÁÑOž E 0 ÒÒ`oo蘂0$Ò»%ˆjàè¦LÁèѰ·GRºwÇéÓ†ŽŒ à ën ¢ÚØÙaË–Òã pù2\\п?ŠŠ”j1KqŒS ˆšC“ ¢FH$ؾÆÁÅ| ¹y³éfÿ3=¦$ãDƒ@Ò-AÔ,• mÛ²Iɇíï˜tnñþ.׈d\‚¨ÿȵ[‚¨YB!bbî>-å5Ͼ­½4WÎÒ†‰ ˆêGÒ-AÔ8.7¥ Ž€Ê¼¨øT2ÆDõI·QÓÔE¬4ƒáp©F)õèˆæúפŒ.AÔs$ÝDM+Œ§Xzr¿¿Û„'¢ÿPß]§4t\AT#’n ¢¦Ä1yr âè'W´=6‹¸ÜÿE³]eèЂ¨.$ÝDM+Œ£Xzp#>QÜ]§¤8è¶ADqù½òáŸjCGWoݽ{·ÿþ¡¡¡‰Äб I·QÓ bi<9­F Ü' D¶Tó~üŽßƒÅõ%Š´SCX?µk×.!!aÊ”)¶¶¶ƒÞ¹s'É»DM"é– jKC’Ä€‚¥×c² ã·Æ®\nÞó„4R2M¹ZP5räHjµúäÉ““'O.Ë»………†ŽŽ¨ÿÈ6Q£$™c}KÄœ‘WMd\ÐdœÓzÏŠ8 béFž\CÇXoݼy³S§NB¡P¥RµhÑ"33S­V}úô=zôСC--- &Q?‘Þ-AÔ¨‚@£Ö¥95叿áŸêÌ ZÝM’k«•¿¿¿£££J¥266NNN7n\hhèàÁƒ)Š Ÿ2eг³³JE&¬Õ‚»lÙ2CÇ@ £W»N<]Æå›P.Üf½ùBK²•cµ£(*33óúõëC† ÉÈȸ}û¶µµõü1þ|OOO­VÛ¦M›1cÆ:L¢~"ƒÉA4 ‘‘‘:t°µµÝ¿`` T*1cÆÿþ÷?Š"_wˆêE“ ÂÀRÃ4ç'Ëž^Ó:ÁÏϯeË–ÙÙÙNž<)‹·oß>kÖ,Òñ ªI·a`… ôã´gÉúŸ2jÔ(èÖ­ÛÉ“'MLLHÆ%jL&+zÄÄÒ=x¤öm͸s玟ŸŸ­­íãǹ\îåË—(“ÉȨ2Q­Hï– Ì¼%Ç9/0¥H%¾šáëë«O¾rå €nݺ…‡‡ë·›˜˜È0LÕÏCÔ'$Ý„á%ÕîQ·“,A©!ÇpúôiÝMýfÜââboookkë   ]»v•””è!b¢î#ƒÉaxÉG5W>–;à÷Ø,2t, BRRÒãÇ»víÊá<ïrœ?~È! …¢Š£Ê< Š‹‹ÓÝ4330`À°aÃhff¦‡è‰º‰¤[‚0<”-NaµæRd¼É Î;7tèP…B1sæÌ­[·Vå:nzzú‘#GÂÂÂ.]º¤Õjp8œÎ;6ÌÍÍMQuI·Q[Ð*hå,Ùï°ô˜quâããýõ×ðððøøxÝç-‡Ãñ÷÷ÿâ‹/†ª‰ºgè‚€äcšë_*ZŽäwZnlèX´÷ßÿرcC‡ݶm€·Ê¸ 䦦ÆÄÄÄÆÆêþŸœœ\¾þ‰‰‰L&Ð¥K—þýûWGüD­EÒ-AÔ æ-8Z+{B¦³^%3®.¹ÆÇÇÇÆÆ&$$ÄÅÅÅÅżô4±Xìîînll|ûöm™LÖ¢E‹½{÷vêÔ©&Þ Q›Ád‚¨X(rYc2’\[¼4ªœ››{ÿþýäää²nkzzºî¢lŠ¢œ===[·n­û‹-ø|þœ9svïÞ `üøñ›7o6777Ð{" ‰¤[B?X–%ûT"—UIX 2cªæ”¤3iá/l饑±Œ®Ä…¶gœ†V··î•ÉàåO˦M›º»»{xxxzzº»»·nÝÚÚÚºü®_¿>a„””±X¼iÓ¦‰'Vó»!j/2˜LèAllì‘#G–,Ybè@ê¶Ì‹Ú Óeöy}÷š:–¤$•¹óƒò•Y¢wwÑäó%Ûò‹”BÀðZnÕÔÒ²í€üàë‹ ¾ôZ†a¾û+WjµÚÎ;ïÝ»×ÙÙ¹úß Q{‘tKèÁîÝ»þùç1cÆ´jÕÊбÔaÖí¹SÊØš ‘‚š"nÎi3û…dÉᣠšÎºI³,̸ֺvñ°rk‘Ÿÿ~£FÊk׌ž>EAöîÅÞ½|¾ñ{ïi¼½³ìæzx°5jÔ¨#GŽP5oÞ¼5kÖæíµL&ªŠ¦éæÍ›?yò¤wïÞçÎ#CÊUÁÒ HyÃai$TßÛ ÒÍYã ±óégç‹·ýôÓO .Ô='//ïRX˜õãÇÝ­­Î;s¦#‡Ã+¿e#Ÿ¯qrZªÕ†æåíY±¢×Œ0&³Í ’n‰*;qâÄ!CtÇÛ·oŸ>}ºaã©ÓXyQ´<›qÀ7t, ­Fâ^UÌvµì)ÀÊ‹klMe^ÔnSL¾–}tÿþý¯+;Ÿ••¥(.vÖh®ÿòKÌ®]},-òò R1@`°\n–™Û¾}“À@øúÂ×—d߆‰¤[¢ªF}ðàÁÆçåå5nÜ866ö¥Ù"DåÄÐ'KEvœÑ×LÉxrÍ`i<üK½I%}ÌhäÁm·X¨•áòB9׈Úd2ðƈK—.uïÞ½2gS«ÕŠººcÇýßïmaá&•joÞä•›ÀLS”ÌÁÁ¬gO©›§CQ@DdçΤ[¢J²²²š5kƲ,MÓ?;vì¾}û WÅâÜD™¥·ÝÇBž1É·Õ‹e|T½EU”Ä0sâø|jäØŸ/{œ$U³¾3ü]뤤¤øøøwÞvñß›7ïìÛ×Û¢EaaÂ8æå•¿ŠËp8w÷½r¥ÙÇŽª\%(.·ÀÚú‰½½Ã!–}úÀLJdßzƒ¤[¢J¼¼¼Å 1·ÍH¹ýʺ¡½»N™I0nLyͺŒ”´Ï‹¢ÃGIôÝcb׉—””äâââì윜œ\C!jµGBB$.{zòîÝS\»füâG4mcÃõ÷OkÜØ¬gOËAƒ`eUCUFÒ-ñîæÎ»yóf]f577/...((ÈÈÈðóócææÍ›¾¾¾†Ž±NºóƒÒ¸1Õj´@`FÒ­~äGÓw~P>ИQ^ Ý' x¢—¼Z9{{…ÒØšj÷±€«W¯víÚõ½÷Þ‹ˆˆ¨ù˜Y–MJHH9uª¯••æÆ;Û¶yÑôË#Ëöö b±ÚËË38˜€Æk>N¢’Hº%Þ‘B¡°··/**zðàAëÖ­=<<âããuÇŸþùêÕ«½½½###ù|² …0¤‚X:rUi¢å‹)ÏiÉB¡E¥¾Ç––Ú+W5zøß~K| ÐÈȲO·÷{û¦#Fp›41è;hèHº%ÞQ›6mfÏžíçç§»éàààÉ“'Äbñýû÷¹\²=Ò;âðñp¿º$É»G7nG~Œo­$ùwõ³D+€ëxA›YB‘Ý[ùËÎÎ`kk[ 1ê‡M»vÁý¥;VJ¥ÿ†…‰ââü(*ëäI^ddc¥aaü°0GóçÃÞ^îáñ@(lܯ_‹1cP;¾F4$ÝïÈÃÃcË–-e7›4i‚géɵUÔîc#¾),ÝÉðÀÛ‘g3÷~V%P3ZP\¸ŽxÍŠÞñǘ••…ZÓ»}#±XÜmìXݱݲe999©IINùù‰ûö= óÕjÅOŸŠž>õpê>úHmeobbÔ¥‹ë¸qð󃽽AïÿHº%ôÃÞÞÏ߈ªk1Œ\ó~;Š\6j½2頚рâ¢åp¾×\#ó–Uú¾R·ÒíKlll`cÀ50ÐUwד'÷vìHúóO.·ÙÓ§‚œïü|¤§cß>9\®ÂÓÓqĈâfÍ8mÚˆ;v4dôõI·„~èz·?6t õÇõ/5CN™5"×o+¢.b£·ªâw©µrœòÛ.Z¸êa|¥N§ÛWhÒ¤í×_·ýúkÝ­”ˆˆÄ}û¼Ôê&OŸ_¸`£P :ÑÑf•H$ôñyboŸÝ´©ó¨Q]º¼c£¿ÿްgY1LÒ-¡å¯Ýz!Ëb9lÖ5­Ó`ÒÓ}5”½¿I•°[­‘±šöâµ]`Ô¸­Þ.dÔ·tû"ç.]œŸ%QRy÷§ü|Ëää˜]»¬RSíärDD4šøé'XXdYYeØØ8iÝ¿?<=Q™Ú_J%¾þOž S':/¯j}GµYDèGjjª³³s³fÍÒÓÓ K=QCsøÐK/­þ¡•l\¨úÁ6•ª`×™ç³ØÈÆ·ª?«ÄÄÄÐÐÐ%K–˜˜˜0 # išV(ÂÿT¯ßhšÆ“'ܨ¨Ëë×s£¢:˜˜23Ë?AÎ秘˜Ø dÕ·o±‹‹Y§N¯Í¾=7oB(Ä?àYȤ[B?Ôjµ‘‘ÇS*•dýiå,׈¢ÈOôZ…¸ßU1¿ª”ù,€ÆÞÜöŸÙwÑÏ@]@@@DDÄŽ;¦L™’››kccÓ¨Q£üü|ÑÑÑk×®]³f^Úªc #¶m+<¾_ãÆüû÷[þÁbŠâûøÜãñD]»¶4ˆ[~Á½J…Ï>Æ Œ­[f$’n ½±¶¶ÎËËËÊÊªÍ 'ê–ˆÏÉGÕýÿ[û>ni¥¼û¿”Ö~oÔšë÷¥Þ­Îï¿ÿ>uêÔ€€€+W®DGG{{{{zzÆÄÄ0 £ÛtñâÅk×®Õc‹uTÊÝ»©aa=LMÙÈÈGýÕJ£)ß·eMM)oï›Z-ããã7kßÛvïÆìÙËÑ®B‹‹ÞPX‚Ðoooÿþû¯¡©?n.“ïl!‰ß­2TjµúôéÓ†j½ £eþPìZê$ u’éUœrRÍ2úoH.—[XXxðàÁÙ³gôîÝ›eÙŸþ€“““L&Ó«Uqú4;p Û¸1Ëá°B!;j”A¢(LMe¯\‘ÿýŦM“YŠbçÿ™šF‰ÅÚ´a¾ûŽmÚ”X33öðaƒ„j@$ÝzÓ¿'Nœ0t õ‡<›QTCV©LÓrùÆGè¼æœT}¿4Ñê^œrRÍÐÕØà‡~`Ñ¢E»ví0a„ŒŒ SSS'Ož¬Æ†ßÁêÕ¥ùŒËe'L`Y__CÇIJ,Ëff–ìÝ{­oßWWÖÞþ…Ô ¨ŸÅ¬þöÛ¿/^,**2t¸5„ÌL&ô†LNÖ;c €$‘Ùræ5´¨¸¸xóæÍ?ýô“nO¥Ù³g×L»ÿ•®¹¿QUOÙqÚ.¶-àTó‡Ö´iÓ¶lÙ²sçN+++vvv .,))>|øÀ«·í·ƒ/¾(=ž1[¶à¯¿°zµAczÆÁA<~|çñãu·ÙÙ‰ÇÆºfg«.]âçç³EÓü¥K¥ÀPoï¿ïÝËÌÌ6lØ‘#G._¾¼~ýú#F.ný«}ÿ6DE6–ªZs…–­¬ÞVW¬Xñ矪Õj...>är¹ ÃtèСzÛ~Qö-í¿kJKÒ Ì)¯Ù¯®”W­¦N:þü;wî8qâ€o¿ýÖ¾¶íqx÷îóckk07Lj† çöïGh(._†BQz©)zõB¿~èÛ-[66>{®‹‹Ë¼yót¿lGurr Þ¶m[HHÈG}´`Á‚ÇkµZGGGü*#é–в±Tup â»MPÕ61ùÎ;Ë–- g†¢¨Ñ£GûûûöÙg@­V;99YZZVWÛ/z¡$­)å5Gè,à›`G­qãÆ}òÉ'YYY"‘(??¿mÛ¶sçέù0Þ °ðùq-ìÔxðg΀ÏGŸ>¥ÿùøà5«ýýýýýýuÇcÆŒqttôðð’’¢ÕjlÞ¼yÕªUß~ûí7ß|sýúõÜÜÜÎ;[ë¾jÔ †¾xLÔ·oßàããcè@êŒÉ¸ )J®– BºþEQ7n܈ÕM šâŠŠŠ¨××ZàóùzŒ¤[â9¥R¢ûœýæ›oÞá º5s7nܨà9ê’Z1ZX·È²è„}ª'W_ñÝ\/®^½Êçó)Š:vì˲ š6mªßVä¹ÌÍeò=E¡N’PgÉ¥92ÉÃÚ˜hutÓµI·• T*Y–•Éd“&MêÚµ+˲ÅÅÅG(ªÕj­Vëìì\ñô¦[·né+˜Z9Ÿ¨q Ãüúë¯ß~ûí“'O(Š ž1cÆ;œçu““¥™'—µO¯j³okYcn›”p}/i¯©hÞ—¯ß-‚urssǧÑh>ýôÓ!C†Ð­ñõõÕWêb6z˳’´€Ó@¾÷¡¥[­ÞZ,:¢ªt¥œD"Qhh¨î†a6nÜXTTÄçócccSRR*>CFF†¾Ö‘tKàÊ•+ü±î¶K—.ëׯç_¯òKidlöMúé5mÖ5maÍ>[‘/0¥äٌȎԸy ÝyÍÞç7{_ÿ°4M;6##£{÷î«V­ÒÝ ]»vU?¿FÊÆüªŠß©VIXö]x>‹HÅÂPÌÍÍçÌ™£;vqqY³fͧŸ~ZÁóu“õ‚TjÐRRR,XÀÉÉiõêÕ£F*%ƒeY‰DR\\,•J¥RiIIIaaaÙqqqqQQ‘îX*•J$’´”T0ÜùýVú©ÇæÝ§Yºô<®’’t&qŸÚ¨Õz†ÞJ=ztåÊ•àÀåË&òùüªìÝH«‘¸Wõ`›ZžÅ°òâú~®çJy¡<oΜ97n|å£+V¬Ðc[¤wÛEDDé†|ù|¾F£©àÉ–––b±X,›ššš™™™››ëŽÅb±………©©iQJŠrÿþ€Ü\K•*ÜE]¾°9ÉCSî{¡± eÕ†kÛgãǵòâqõ–2ŠìÛÚ–XO IDATÓA23'Îð¿MõrÂääd??¿ÂÂÂuëÖéVÙV®$mô&•ô1 ‘'·Ý"a³^|r©^ÿHïVFŽyøðáò÷P5oÞ¼ 6è±ò}³!êÒ¥ËáÇׯ_èÐ!]®uqq4hP·nÝÌÌÌ,,,ÌÌÌÊRlçanÜà¬\É„…q†ÃátîŒ9s¬½ùæbNQÃS=xò,6ÿ­Èa3/j3/jðM(+o®µ׺·q;ž±5ù0~3kžç4aÓžúù›•Ëå#FŒ(,, ÒK®e$UGoV=b˜9s|>1rìϧÞòýN碗îqèÎëj¢;ÞÕª¨ì EïßLšö"Ÿ`„:tèÎ;k×®‹‹ãp8^^^_ýµ‹‹‹~[!½Û-''ç÷ßß°aƒ®§kgg7kÖ¬yóæ5nܸâÆ„„hW®l+•`„ÂOOçŸnÚµë… úôéÓ»wïSGÏ]Y¤È8§¡¸è°ÄÈcа$É‰ÔæGÓùè¼{4S®G-0£¬¼¸6~\+/®/OhA²oµ›>}úo¿ýæééyóæÍªNÁe‘zJsïg•$‘`ÚœÓv¡°ÅÐwÜçY’H‡id¥ŸK~_¹} à—þJ¨ Ùk_*ÒÏhºÿ"rذ;ͤw[×tK@¥RýùçŸkÖ¬yðà¡Pôé§Ÿzyy½ôLµB‘ÒòÄ ]5’b.×ìë¯1glltO8wî\ß¾}ßÿý³gςŃÿ©î¬V‚…ë8AÇoË ¨iålA,MçGÓÙ‘´4ƒ)ߊisŽ/×Ê‹kåÅmÜŽWÝõMõ‹aÝ•o¹\.“ÉÚµkÇåêmbXq*óïj%Wˆ®ëEU9Ïo¿ý6}út33³[·n¹¹¹UåT4÷QåEÑD¶œ¶ …U¯”wk™"n§ZwìÈï¶áù›eix¯XhÁz¦Á¯Ò© ÝbåJܸ^½ðùçX¸`íZ¼Óê>B_Hº%J1 süøñŸ~úéŸþ ‰²²²ž&+•²Ì[ºÔQ«‡èþý]CB„/öƒÏœ9Ó¿ÿ~ýú>}ZwOj¸&âS…VÎÚør{l6ÑÕK‰<›É@çGÓ9‘tî¿´Vñüw’'¢yr¬Úp­¼¸¶þýïêg•òÌ(¯õ\’Ö̉Ӵ/óo-F‹„=jŸÅFº‡þ©æ‰¨–#j¤Ð|­ñòÐñâÅX¼{ö`„Ò{ââ`f†äd,XKK$'“®­Á‘tK¼¬}ûö»wï@gfr׬1ß²¥¯.gøûK?úÈi̘×U¬Ä«Ò-+/n`¸øò¹<‹1±Ç2Å……+וÛrh¤la<IgßÖæE•Ÿo¥¢¸0oÁ±jõéÀ³ñåZ¸pkòJ^=6mÚ4sæÌ²{¼¼¼fΜ9}út##£êk×9°ôKÉ;\efÒ¤Iiiik×®}‡Ö bèÈïK-_LyNxLVǵv)B]º¸Oí=߈+€"͸ q#à‹ò5[ K¼qTòÂØÙÁÅáÞ=¢wï Žx-’n‰WxtútÚôéݲ²@ÓÆÀ]óU«ZLœøÆËe¯L·„Tï&Šæm?(ùbÊÆgãÇk3[@žÍäÜ¡snkóÐù÷iÉCFòytD£{¦¥;ÇÆgãǵiÏVÿ2ß3f$%%­^½ÚØØX$EGGÏŸ?ݺuóçÏŸ6mš¹¹yu4ªÈa/Í‘©ŠØaçÞz9ЪU«Nžÿí:ˆEÉLÔ:eê) Xp(É‚63…Õ÷CnÀ3oÅ)Jb(óÙÔê–#«Yn4ìaäJ:ÎÎèÕ .^„£#Zµ2tL ¹vK<DzlÒþý.üðp0 °ãÆñ>ý>>•<ñcdž 6tèУGVk¨- ãè²ÙÎ’‡/Ì·2¶¡lýtk|¹VÞ.>Ú§DhA 8Øà'I½QVìíqâ€!C`míÛ+—"j‚¾juöÈ‘»&&¥FŒŒú÷Ï­°°Ï+é–Š>¼:"¬˜<‡I?¯¾»^q~ªô¶E¡N’²ÿvµ’œ,¹¹LžtHU˜ Õo»%%%ÞÞÞúõë§Õj###ƒƒƒy¼Òq£.]º?~œaôY)ï¾öm«*¥¤¤4jÔÀªU«*ÿ*ÙSúÚ—òJÒ>®¹>9Sþß1z«2ÔIòè)¥\ {ö°b1«zV ÙҒݹ“ݱƒ}§ªš \pppùŒÙ¾}ûÙ³g{xxˆÅb>Ÿß´iÓ &ðܹs7oÞìîî~ëÖ­Š·  .b£·>«”GÁi¿íB¡…«ajJH3‡»—”m#Õf–Ð÷‹jœ†F¯YV$ÍÍÍM÷ç 77×ÑÑQ¡Ppppxôè‘®ÞßkUo?œ¨•²““ä>:Î06¾·x1«TVýÌûöí0vìØªŸªúȲèôóêÈEø¨’Ýî/ ;ïm]>ªäæ2yÊIµ"ïílu5ù|þ¥K—ÊßOÓôñãÇûôé£û‹ãóù£G¾víZUÞÂÉ%‡ºÄ¿y`\•H$ºÿ~ÅÏT3‘!н­K —æÈ âô<ðþþž-Óų³…¤$½öÖ¢'ê±Û·o—eL77·ò >¼ì¡Ã‡W|23¹a‰ˆp?w®ñÆ£ h¼½ù+V44¨iÕæP( cccügf2MÓzÜSI_þ»Ì·l¶³$©t™o\¨oYVaÒ¤I·nÝÚ¼yó… ºwï^v?‡Ã ŒŠŠÚ²eË®]»8pàÀ__ß Œ?¾ìBo彿˄oòæ~íÝ»w?üðCÛ¶mûïae´ 6~çóJyöïñ|Y·¯ÿpSi§5štãÕüh6AT¬]»vGŽÑGDD”Ͼ¯Pß ˆÚ$==¬eK©n&ãêšñûïU?k~~~PP›››V«eYV·`÷ƒ>Ð=ºhÑ¢AƒÅÅÅU½¡š¡*fž\Õèæ[íóy¡ã»³¥äèûÅ×¾|6ßêU]_FsôèÑŠ›ÈÊÊZºt©µµµîÐÙÙ9$$¤  àBM?_Ѽ!‰D¢Ûc}æÌ™¯{ŽVÉFoQîo_úNOI³okÞ6’êv|`I¨“$ãÂóÀTæöJEø¨’»ëñ¹|o›¢„}ª NBflÞí¯¿þZöЧˆ’t[Ïi4šÓ?þ˜7p Ëç³d´kÇ^¹¢¯óÓ4­[ëʲìÎ;Lœ8‘eÙŒŒ ¡PÈáp¢££õÕ\ +N£“©n.“‡*Ùå")Ÿ}ÿð*:3Azw½"ý¼ZYøÖ•JåÎ;Ëzœ¦¦¦3gÎŒ¯ìëö¯NÅ¡N’ÂÄW¯2 3dÈ:tP¾ê2£eþPè\¬{;'—<¹ZëmŠSéP'Éã+š»ëŠ|æD`ɵ¯ä†ЍŸ*H·{÷î-{¨OŸ>Ÿ‡ &×kׯ§OŸÞ76–Àç«ÇŒQôQÓNô؇ÃùüóσƒƒW¬X1a„òƒÉßÿ½J¥ ÒûÚÓcÚœcÚ\ Ûßê¿ežFhuû+áíË*…‰'Nœ8ñêÕ«6l8|øð¶mÛ~ýõ×.\¸°ìBïkQpèÎ+zÄh¤¯žê¸víÚãÇ7nÜøàÁƒ/Mß(-I»Y%ÍdXºs}>©{%i%I4_LIÓÉB¡9U’θŽ%S–‰š¦ÕjËŽ¯Ú×¶<’në!¹LvzÞ<Ï'Üóó[J'±[7ïÐP£cu| 7nùò剉‰(K·)))Û·oçñxË—/¯†6 €'*ÝßJwó¥² %éLIzéþVoUV! ))iãÆ¿ýö[XXXXX˜ÏìÙ³'NœXÁ~ï…¿î¡þù端¾âr¹ûöík^~퇮RÞOJÝ– ¦ŽœöŸ½KIÚÚàimlM™:q„TA­.bí»O3¢¦=/ÏüÆb$ä´^ÉLMuøç£µkGmÚ´åË—üñÇ8NHHˆF£ùàƒ\]]«¯iÒoY…V­ZýüóÏß}÷]hhè?þx÷îÝY³f}óÍ7³gÏ® üpq ó䊶åH~ùiS?3fŒV«]ºtiù^rj¸æþUa @ÜŒÓî#¡óAÝ*nXÞÓ­¸Çþ=€¬kZ±ÇÔ±~k ê¸Ô²¢L€Ï›vß#ënë …"lÈ6.8±,Y£FOÆs A+‡WŽF£qssKII™5kÖÿþ÷¿±cÇ:tˆeÙ¸¸¸VúÞ©u§sÑK÷8tçõ 5ÑïjUT¶L³÷o&M{ ŸhdlaÜó² Ê‚W,ó­ ¬‚n¾ÕO?ýôÆý O•eßÔvß$rXº²Z­îÑ£Çõë× ¦Õ¡½»N™{—`lCµûȨê%i K‘Ëþå_\öï{qºÜÈŠêü½q]즵ßëÖÝèØ±ã­[·ðlH¯yʼnTßåe¢f\9~øàƒ-[¶ÄÄÄ:tèálj‰‰éééIII=Z±bÅ?ÿü£Õj»wï¾qãF‡šùq„A”O·666nnnqqq‰D,{zzϘ1ã¥ý|’’’\\\Ξ=1wîÜøùù‘Á交¤¤Dsõ*3h °Ãå²ÁÁì½{†Ž«”T*ÕÍÍ©©©ÕÚÖù)Ò²!Ù×*Êî¿8S¶Ç³èm æÔŒ–-LÐê–ùž,ÙÙâ…aç?ý‹ÎO•ÞùQ¶cù‘^=žïÙËcÄ×ög#V縹¹à¬{án7IdˆB‘ÿÚŸCIIIrròôéÓXZZ–¨¬¼Drr²\.OMMíÒ¥ €ž={=z´_¿~»víúí·ßìíí´mÛV·Ã AÔWå“Û·o_™—?~ÜÌÌlëÖ­ùùù ÃXZZnݺ•¤Û:ãôܹ7x<ÝZ­@Ó§&1ÑÐA½,$$À‡~XÝ =¾¬)KEû}‹´*–eYy.³³¥¤~lw ‘1Ù·5±;”—æÈþô{y«õ®ñš*ä—.²0µà(ôÞÛUrs™\ö´RÛ gggëΞž^þþqãÆÈËËÓÝ 0zô课úªìâñ®]»t¯½|ù²~ß;AÔ*åÓ­§§ge^²páBWW× .°,àáÇäRGm—”ðà³ÏàãÓoÓ¦ŽZ­\(Äҥ܌ Ïsçx..†ŽîeóæÍsttüæ›oª»¡&<óV¥¿½Ê|6õ„À£Ãj–†Ûu`ùtË|=¦»o¾i6ô¬i—5Æ®ã<¸,³ÚŒ(ùq•ííæó9f’’BrºØ¢{Éà0Sÿ¥Æ•¬¡8°páX¸Z^(«ÐÂöÔòâÉ[ófäP馎f£v¾õ²+”””ôôôòwž>}ZWÛ@jjjff&€¥K—–¯•«›$ÀÌÌì]ßAÔCYYY111º¡>ÿýwïÞ½†!½ÛZ‡eÙKGööf›ÿøc ËÂB¾e •’â´~}mε:5ÓPË|yé§~4ýઢGŒÛVí©(.,\¹Žø´Z%žj¦¨þÕxy%ÿº¿}¦,´D£z›éºÙãe÷dddDEEën^ºt @«V­Ê¿°¬S«[÷Eõ’F£)¿ÐV&“EGGk4š ^rá±XÜ·o_ÝÍ«W¯vïÞ}çÎ$ÝÖ"4M«SS©>ê0jÔˆèh*'þþÌÑ£vùù¢Ù³ñ¦ 9ž1åôügòïj¥Ð’rX—·o¨–AÜïªÃÝKROjäY= õpáÛ;ÜUÑSrŽi%Ë TYt¥²n“&Mðbºýꫯ6nÜÈç—þ$uéVwù¶¼³gÏpuu%é–¨ÇfÍšUöÕ@ff¦··wïÞ½+xÉ… z÷î­ÛB™eY‘HtêÔ©Þ½{“ÁäÚââÖ­EŸ~:D©„Vk<òð°Y·ÎtÀò…¨î“±;Tºm¤X.An¹ï$×¾PäÞ¥E¶Kƒ¡Ñv¾°l«[ôˆ¹þ¥"û¶WZ Æ5q`œ] 9²åqn+éo UË UE¼…‚>ƽk[[[es¦ÂÂÂËwdué600°ü«ärù©S§,Z´HÏï j“;vìØ±ãm_RvLQ”îZ òan`‰$rëVöœ3g¸TJÑ4‚ƒq÷nËØXÓÞâDgÎ`Ð X[ƒË…‘F®¶k±§ùû¥0Š· / HÒƒOˆßßeÒw¯I“Þ…©²¢GÌ«NS70Dý¤<1¨$û¶VdÇñœ!¤Õ°tçf>g—æ»v¡]»·;Ñš5èßáá(,ĸqhÒ f²¨Ç”ÒÛ¤OÜì…ßçÖÓ…e]§Á|Z¬ZÔM¹wé°@齟UŒ“CÏŠóþÕpû@P:©¸…K_·1—:§ÐžRhÃíE™Ž¦K-…8” —â½~;)KKK………*•jÖ¬Y?þøcÙ¶‘þþûo=zôà”ÛªìÉ“'!!!‡*ÿd‚ *@Ò­ÄÜ¿¿½kWmÛ¶VS¦t¢iŸ/Y¸©©ÎÇsß¡~NL ¾ø¢ôxÆ ìÙƒg3â[^#O.÷à—'I9x~—Q³„æuoC”½þ•"|¤´0¶páôÿÓÄ©qI*“s‡˜SV½eYYYB‘öÔÌa;‘€ÂÆ"õæ"uµ¬‘ð‘£ø«Š¦éÒm~~þĉ.\جY³òêF’;•«‘¬Ñh‚‚‚4MxxxË–-«å=D}D¾™Ö(Z.çnßÞhÉ’2ØÛk-2™9UYJ æÙi¯^ЯRŸ#ðä¶GfiÄý®nÔšÛ¬o›H•vJsë[¥<›á Ðîc#ÏéB]ɼ„=j­F R2¢¸º¸Äs¨Hí#àl±6ž–£X˜¯tpúó,8”§¢/b±@VVV¯^½tËË»xñbÙsdggOœ8Q*•^¹r忊‚¨@úP6¬;—/GNž<>'ÇT&³r-,˜¯¾²]°€/¬ò•»wŸ[[€¹9FŒ¨êië…’tæòB¹4ƒ±påv]/âÖÉÝò,æúEæE-»Î¼Î«ŒÍœJÇ¢T…lòq ÅûDÁ±+ Ü]]ÜÛ*ú¦ŠžjÊ¿¯¢.Re)n45qå¿aK(X¾|ù¬Y³^z(11ññãÇæææ—.]JHHP(ºbº'N$cÈñ¶ÈßLõR«ÕwÏŸïxëV» | °¾¾ÔÒ¥Öƒé­nOaáócò!ø"ÓæœAGÄ2ÿÖ†v\fÔrdmO¹,ƒøª¨õ*u ËS~_¹Ž”/‹ûð€šV²Ýy¦ŽœÄ߸¹¹55æÞVÑWtocÞºÆF4L˜\;à©ü¦ƒIcnE½[[[ÛcÇŽ 2ä¿ýóÏ?ºuë¶ÿ~=¿I‚hxȧs5R$$ìóó#•àÙ:˜¯ZeÔ§ž›ÑÖÕé?5©iOžC7ÞÝUµ<Ý%1×¾TäDj8àw\fllóB²di$ìRpŸ(ÀÍÍÍĈ·ê«JøÃÖ¸ËcY´š™-?go"x}Âåñx¯Ìµx–n»víª¯wG ™*¥¹¹¹?ÏœY $'R+²ãôúUÔc³è¥\ ó’Fú˜1mÎqèÁC¹tûžט‚ѳ§›r¨ãö".uYAÏÉS¼[HW¯^Å‹ó¤‚xg¤w«O4MsoÞ|:nÜ‚ôt Ÿ¯3†÷ÕWVÞÞÕÒž¥%Ǝů¿âÙ˜8ÍšÁܼZš«S4R6n‡ÊÆ·´{q*“yAÛjL-íÚfÝÐ^ÿRQœÊPxL´[d$0}u‡4~—€ÛІat«€\]]͹T‘³¿Ü‹œxœCv¢>Od¿kÚ ¸óÍßî½§¥¥¥¥¥QåããóºçWi’A4($ÝêGJròþ>™”äš›ë ¨x¼¢Q£lBBŽŽÕØªnù°°çévÆ ¼¸±mƒ%° ùløH©qce>ã=_è9µÖí¨¬‘²‘«”‰ûÕ`aáÂé¼Jdã÷Ú EÉÌ“+Ú²Ý+333 …¹¹9þt€÷ÖÆ“sç)[ð9ƒDoñ÷®+8oiiY6-ù% ƒ¡C!aÇØÚVþÄÑ@‘t[U÷ÿý×ûÁƒ¦ßÿe|<°Û}, IDAT¶Q#jþ|á¼y6:´M`Jõßobè(Þ í”ææ2…"‡}iÏë$ìQƒ…óÒÚ e]Û ^2É”ÿ@M¯•¨Çg+"LÚÞ|ýH"‘¬X±bóæÍ F=jÔ¨1cƼô´¤$Ü¿Oosþ¢~#é¶B.àÄ ¬^ýÊò¬L¶ÑÛ{Hr2> ·²Ò,X`¾x1Ljû§022t¼åÄÄ ¨èùÍ[·Ð´)_˜½5jÔócµ,-k*¾G·Îçî*”ZPþϨåðJ­óy´p²€µtçÚú¿ð×ZùiÉÿeLá˜Èÿ±4BIÏÊU„êu¢rVVP(ð×_HJBN*7©‹ ê'ŠmØ3Ÿ>}Ú¸qc–e—ØÙ­)_Éîõ/€]õÇU9¯Þ²qÏL˜ðŠûi~ˆÈH\¿Žª×Ù%þC’H_ÿJ¡+à4ï¿ÌØØºªCµá#¥¹ÿÒW»Ž{¡wÛ©S§›7o^¾|ù+öÜQÑÝËå,»ÚÊèS‹jÜMZ*Åß#0OŸâ»ïðý÷°°¨¾Ö¢–jнÛU«V-_¾|Û¶mÁãÇ0lXøéR©F© (• •B£P»vŒêÒ¥²ë-’“1~üÇŽA­Ö-¯#ˆ†¥!¦ÛëׯK$’ØÚÚj4šøøxp¹mwì0t\Õ©E ܸááèÜ6`Ò$CÇT<½¦½þ•¢$íÝ×ù¼NÂ5€–£<ãN˜““#‘H,--mª¶Äh1ÿ¾šYQ¨ú Gá ò¼õ¬é·²f ”J¬ZÿîÝÉ~ËDÒà“/^¼Ø»wïV­ZÅÇÇÓ4––æââbè jVPnÞDZš¡ã¨T…ìíååÖù|/²ñÕ[ÆR²Þ+aÔìð‹¦¦Ž/䥫W¯víÚµcÇŽ7tߢª€Æg+öK5Ž<Îͦ&¶Õ3Qù%gÎ`à@ô뇰0’q‰†¢Aü¦3 ³wïÞÁƒ«Tª=zøûû>\©T ‚úŸkÿŸ½ûŒ¢êâüŸÙ¾ÙtÒH¡‡Þ14¥ƒBè UA|A±Ð‘ª€ˆ‚‚´€ˆR$Ò{1J'@ @Òûfû̼6$RÉîÎ$¹Ï»³³3'!»gî{ÏMIÁÅ‹Ïm‘Js»Ê‰ò‰Úg8Ø;;j¿Q$AëYòÀÃö̵ün`tœ÷âr-,Ñ“œ‡¶¸+ÚÉD­9PùR)ÜÝšËÚâŒÁ»JÞ™¬Õj(ŠU«V]¿~}×®]&LøçŸøŽË†²³±f :tÈ}úàz® 4Qv9OÙË ò×óéðâåŒXNƒˆ Ær£Ý‚适Â/e»Øœ‹:fR²v»u*Ôµ+nÞ„‹ Xo¾‰öí±`DÖíÉ&žUæÖí®]»jÕªe^¶óË/¿üá‡FŽÉwP6ç₤$tè€Aƒ0hÆÇ‚X±‚ï°**ŽÁíŸôzªcOšdNT§ÕŠÞAvϵbOÕq¬C-Ú§K!×Ä¥Yé¶L¼DÔAO…MíÈ6~“®·Ôa‹áæ‘gÏâøqlÚ„´4œ“ øT [·?ë­·T*UbbâÅ‹?ùä“@óÈÈ*ÈÑ‘µ°”ŒûÌÅ9Úä«–œçSs‘äú# Ÿ³kÙÖ­Y+™h›»|X‚v^š¾Ž„®²Åj’]ºàÈH¥pséSе« NK<¨lC¥"""š6mjooÿøñc;;» .t*tf*A”£Çõ5–ŸçS”̇ìÙb5ì’½Ô!7ߪÕj•JÀd2ÙÙÙ™L&µZ­PX¸ãwqº~Qš^Aጷ][™íºwм9RSqútá“É ¢¢«$ɧN LKKkРAûöíû÷ï¯Ñh(Š"¹–(¿ø ¦ƒ½³oÿ¤çX4/pTeÕ\ óüµûK̹–a˜ž={º»»gddxôè‘Á`ðõõµx®ð…³l”J¢å00Ag²Ýµ¸›&MBïÞèÐ&RSmvf‚°‘Šn9ŽÓétV®\yèСŸ~ú ÀÉ“'ýõ×rÎG$útîüLÍÑ19ÙY§ú¢>¿«Ú-THTÖ*cTs‘¿4xV$Y$±,«Õj:„—z’ÿý÷/¾øÂh.ÃRn°Ù] =5q4[õ~‰DX²!! iÌŸ–-qåŠmÎL6RÓíñãÇ6l¸xñbóçÏÿòË/'Mš@D8–µÏp°Wy>©,;ϧ(9œG[±KÃüÓ 2À¾}ûð|µä˜˜˜)S¦|õÕWÁÁÁ– @Na¿§²†˜¾¢gÆ'ély·‰¦a4âÌ<}ŠŒ ž˜ ¬¯â¥ÛìììcÇŽprrŠˆˆøë¯¿X–íС Ü*î¢=„¨ãØïæœÿD«Má¼:ˆ}õõ|ʌýíz¼´þÏ!CD"Ñádz²²Ì­Ûúõë3 3räÈôôô‘#Gšó±¥xЍ`O…MíU—Ød r‰§N!8Ý»#! ÂBív‚àY™œžž^¯^½œœœèèè6mÚ:t¨W¯^4)KCXÇ ügýuz“Ö2ëù”UÂ?¦Œ¬Ò“®ùæs·‡=<<:tèpîܹÐÐмÎäeË–]¸p¡fÍšæÙn–ÕB&Úᮚ Y˜¦¯'¡GØd ²™\Ž·Þ€Ñ£qâÔj¬^m³“„µTŒDõàÁƒ÷Þ{ïáÇÎÎÎ:ujß¾½yÌHß¾}%Û} •[ê-æÐõ•å:“–«3H2à¨}Á6͵x6ÿ§ÞÛê¥~ë¼þdsg²F£Y´h‘H$Ú±c‡“uVØd'þÒEÆï&iÃôŒ5NQ¼¥K€Ù³ 1Ñöç'KúD †aD"Ѹqã¶oß>uêÔ 6hµZk È$ª2“†»ºRwo‡c`çE,Qøtã¡ãG“ÀþÑ)›¢1ô¼ƒÂýÅ<ëëë«T*srrììì<==£¢¢>ÿüóåË—[/$›¤Ý™môQa>v>b~.ÐGÿþøö[L™ÂËù „ۺ½uëVÏž='Ož àóÏ?Ÿ:uêgŸ}€äZ²â/˜‚ßRßÝjrçùð’kD85ûH^ε|||Ú´i“““@.—GEEµmÛvÉ’%V ‰~vS´—‹ân@‚6‡åçêüÄ hµˆçåäa‚kÝšL¦K—.uîÜÙ¼V££ctt´ V™%*‹çÖó©/j¿Ta›±Ç…b ø£}–.{s¯{›ÂóýÒ¥KçÍ›çææ–’’"•JÚ5kfƒØ®]lÎ;ÄN²×SaÛþõ\Ç£{w°,-ÂÇÃÅ… ¢„Õº5™L7îÒ¥KDDDÍš5<Er-a |Íó)ÊãÃF]çÚTTT®0|øpÉÉÉÇ­ZµÊ6¹€‡ˆ õR:ÐÔŸ9ÆÅi6¨œ§GP/Æ’% „Àš Q2A¤Ûôôô¯¾úêêÕ«b±¸K—.uêÔILLðæ›o:88ðQÙð9ϧh÷vè4xGZÌ>uëÖmܸ1€îÝ»ðÁ6Š ÐHJÿæ¡_¦ëw©y›š3e :wÆÊ• (deñA¼ ž;“Í#¡fÍšµbÅŠ¡C‡îÝ»733S¥R‘R„5<7ÏÇ™j;ßÖó|Š’z‹9Ô_-s¦†]´É‹ è‹/¾X¿~ýÍ›7}||l^ž†Y©:9…SÕíä|~H<@ûöxï=,]J¨'*Þ.éãââ>ÿüó´´´ÐÐÐéÓ§ß»woÆŒù ‰¨ÜRo1gkÓî0ê ’´žcÅõ|ÊêÞ€ºC¥ÅçZƒ jذ!/¹ÀçNÒH#ûs–aP‚&ÌÇ®O•œ?ôtܼIz•‰ ƒ‡Öí7š7ož––æççg0!LF£±~ýú X³f ß±äJ¹É\š#Ðy>E [¬½»ÕP”´ý×µ¸‘CŸxÍI­©‘”¾ämçÀß@å<æ)¹mÚàÏ?I3—ò^fggó*Ãð°ha[·nŽŽÞ´iS¼ÊÆ›4\ØbíáÁê´;Œ]uºûf»Nß*…Ÿkj.r¯Ž«M[3 …½žŠzúŽ‘¨Â>;4 ™Œ ž"„¥¼é¶ø¡Å2YÅ»E”H¯×õÕW´ZíÒ¥Kù æéYÓÁ>‚žçS”‡ŒÆΣ­Ø©~Å®¡æBSÁ^J'š Õ˜æ¥ò¢bÙ°aôiÓš6mºsçÎæÍ›7iÒd÷îÝÍ›7—H$‘‘‘V]¦&åsiŽ6íî³y>sŠjä6íK®­ÖÝ\¯¯=@Òy’ïX,/åbsîÙ>Jñ!/¥@Zï?þˆ®]áïGP«ßÑTao¿ývÇŽ§OŸÎw <¨x-‚/yMÛ¹sçÒÏ–mÒ¤‰¹»bÅ +7wžÏuÚÝó|*l®eô¸¿Ë AÅ)’\&Î4ì¥t¦©¿5¦Y©BY7`êTøûãÜ94i‚÷ß'·rùñ矮Zµªj6pIº%JË|×¶iӦÇ/¸}ñâÅ4MoÚ´Éwp_œçs¼ÂÌó)ÊãP£.sm*ro-†Ÿå5Ð<•R «3 0P9OZL&¤¦’UrùñÕW_1 ³e˾cáI·D©°,ûÝwߘ5kV^ÓÖ¬I“&}ûöÕëõ6l°àu©ùó|\›ˆúPµž%+*j£6yþOƒw*Û]Û¼®m¨¦ð¿Ý)a T0`Μɒ»};ªd‹7¿ýö›¹lþ7ß|S¸$Ý¥BÓôáÇgΜ9bĈ—_]¼xñ7ß|3oÞ<ËœÌ<ϧ{þ<Ÿ¾T®M*C[0õ“|‘9SµT’ù?Řè ùŸ£ÔÈah‚6R•Í •bõjŒ‡!CH3×v.\È0 ÇqR©4&&fãÆ|Gdkôرc©Z·n=uêÔFÙÛÛK¥Ò5jŒ=:<<œï8 þÕ«WoõêÕ"Q!i¯eË–³g϶³DÚ̇ìß#^œçSif˘çÿÔ&É+|3½4¾«&ï«§±\`¼&C•óô뇚51q"Èe¶qëÖ­½{÷* –-[¦ÕjùŽË¦è_~ùeëÖ­yÏïÞ½«P(-ZÔ¦M›ØØXóƒ'Nð$Q%°F\_£ é«N +Û<Ÿmµ2_øw||~¡íuó·Çžä³WS—Ê=:h DhP)*I•†Øå¡h"¥ïÙ·µ&Á$Ü pë BV¦NEZßUv_ý5˲£F P(Úµko^½ê ¥RiãÆóžûúú~ûí·Ã‡ïß¿ÿÁƒÍ#:nܸqU°«°™”Ì¡þêkõŒŽ«3H2à¨}Á¥];oÀ•Ä.×6så]~ÌŸ`óö¿¾½%ÞX¯ôéÊç0«È½ÆŸ.•wº‰ã@SÁžJ7uTcúT0•ØÛÀ´iøé'LšÄw4uYǼŸ¬k›ã-}˜eÿ(»IŒúƒd]¸Ÿ.}sÓV©T~ðÁæ-_|ñª^·¸½››[Ÿ>}Ìãââ>l“ˆªÅ˜Ã]š«=5jó¿8ãΘ´Iï#cOsž²Žµéê+öD¦WÓY.úÉM`FŠî„`*ðòÂáÃðñAh(4@ddyx×ÀŠ£²¨¨¬Ë:>W#ì(mwWŒRI^WˆÞRŠ×T“Ïq–™8¼Ÿ¬K`lÚ§Ÿ×´5kVÁíU°[Bº-¸¾ÞÇ­ Q…˜çùœš¢Ñ$X`žƒíÓ%7±&DìÌoB=Øc+©:ƒy |o»@ƒÑ¥í!¯|&ØK>v’9 OÐÞÌ@å<Ë–!2¿þZÞãÌNã5Í> {ñªn„J@Ãq‡56½ÜÉkÚzzzÜ^¸%¤[ó½[³âW’'ªsíOêÕ†u¾´žEæù4œ_¤éþncm sÂX{ D¢â3ËeF±OÏ›$vTÝáU®'¹ U®ò@;qËõפ i 2€ýû±p!¾ú ’’^ñ çuLpÿm÷¹ÎÒE./Ö,óç~âL6½ÖiÑ¢…Ï'Ÿ|òòKsçÎõ÷÷¯:+ٔЯe2åÿéH¥Uú›‚°ˆÌ(öÒ\mb˜ €WGqû¯–Zc z'±c]:3’ Kå¢C u†H£ö8 Fóü§±SµJ 骂h È]Ñ1.ç–};A{ØK)ÌïÃÅ‹ÀŒøí7œ9ÿ2¼ýˆÆ´&ÓpV›ß²m—@˜ê8”3¶St?d–|Ï»»B|¼º€²°ë`ã³Ë‘Mé³gÏþì³Ï @Ø¿ÿÀÀÀÊæTb%¤ÛÌÌ̼ÇîîîV†¨ÌX#nþ »ý“žÑCæLµ/¯3È¢=«Ž—]žŸ{èî6C!ÒÈß î­E. ùœ·kTs‘{ à?®rI.{š öR¾›sLkú(U·¾šœïˆž£Ó!, é鈈([ºå€Ö2Ñ=£y–pÇÛK¼Å´Eþò؉}Jqaâ'..oå-‰ØHjëC¡¹€¹ØƒƒáQ é6:::ïqË–-­ Qy%_c.ÍѦGXw=Ÿ:ƒ%WWê ™€Ô[ÌíúÌ(¶ów<¯ºóð€Ñ˜ÃyˆêU•«øâù‰é}žÊîOs~È44”ÐÓÔm&—ãÈ„…¡G¤¥A­†¯o©ÞØG)î£È1&?ˆô¾ƒ4@n™ÄÖS!î©(ï»_³šIE,QV%|þÏŸ?Ÿ»M80oû{ï½×¤I“Þ½{wïÞ½K—.Ç·bŒDE{Òù‡/Ý3Ïó ªN`TÞt÷-V\ÏG¬ ê¸9zu…NæLÕ|‹×AR\n‘ä*8ÿ§å¢Ï*ÛxäN‰УRRн;ÞxZ’–ÃE39Y·)Ëà-¦~÷T‹>¾wÅtîܹ°°0óã‰'ú¸Ì»sçΕ+Wd2€¯¿þº_¿~ׯ_÷/Sç Q‰˜4Ü¥yZM+µ§Ì5%Ìÿm [¤Ó$²”M¦ÈšO—Y{ÿqÒ;[ô‹zÃ¥¢çÓÜ…Ï´iw¥Å@Qh>CîÞÆŠû —MX¥'íÛ«òI.“qö’p³2Ã02Q{ÑÛ®±TXY@©„ƒŒFX¢2)oŽjLoÅk ¶„žå$ûÌIêjÛ·DA/¦ÛGõîÝ»víÚ&“iÏž=æ]ºt1¯“gæÌ™æ\ `øðáóçÏ?}ú4I·UÖµoõšÖ3@œ—T4 ì¥yZsÑDצ¢ß(\Û¢ KåMûö”<þÛ€¢ Yx'ëÓ/Xe.Â|ý;ݱ±9ýCU–®õ2si‹ïH+MÙg Zæ*¿odæ˜4aÞvÕ„” ”Jìßnn¸x~~¨^·`R®4§•Uýù[¼v4ÅAŠQ*rµÇ¿Ó­“““V«ýã?222T*U‡Æ€Œø IDATŒ3iÒ¤îu:4ï±Á`àììlƒp J»ËÜݪ§Åxm±8÷¶é¯¯Ñ²8±’jõ©Ì¬M×h8AjN·Õ_«j¼˜G›ÏçS+PzcþéYSƒ1Véé͉gŸ5Šd¨?Šô$‚vº+:Æin˜Á šãÕí¤J¸pq‹ .^D¯^¨Yçσ¯/¹Eéú2LÎã&¢x é:¦*{1Ýúøøœ={¶ôïgfíÚµ-[¶,xg—¨B8üó…–cÐð]™S}Qf${i®6ñ_ËÏó)=vb—F¢´;Œÿ˜BF,êÄš8"«½¿ËÀ1¨(‘»ï»Â©h*ØKñZlÎ935Y»Ù]Qò{l«aC4h€-àPÞé<¯î={I—RŒoòxid²»ˆà@“??Ax1Ýêt¥­!þðáÃQ£F=zô¨qãÆ;wîÌë[&ª”¨ý†¤ÿ¥Ýì²ëk¬9ϧ,ÿR•f·´p†ÃJU=îï2(4ëyjŠé}žÊnOs¶d›ÉD3„4P€³3NŸ†JßqãxÈ»-d¢²Wé r¢©1ö’êÅN"læÅÿ†)m²Úµk_¾|911ñÓO?mß¾ý¶mÛ,!t‹ÿ–êÔ!ýûíœkõŒe]χ/¬ w6šýO®ô´Ê—ÑãP£.sm*rkEnÛ– ƒ\´Ý]AŸ¤è l 2{{P¾üÓ§cèÐ ¶"ývwéL |ѼõÖ[½{÷6×›&ªm2«Kå”îôuºŒûVŸçcYa‹´ÕZŠšÿÏZMÏÜù?¥¸+\QÖ뵪á*ÉgŒJÔÞæi¸â½û.7Æœ9Å­H/)ðš^Y9™áVgN iMˆÒøõ×_©Â <˜ïÐÊ…6÷îÝË{ž““sëÖ-£±¸EšRRR.^¼Xp‹T*U«ÕÖŠ‘*}š$€ß[’6óäºTöæzý? µ''kB‡©9!~m‚cpq¶VîJµÿZa¥&xÊM&ù#w¥j (9ÝV”õz­m‰‹ìm•$›åã5ɶ]µ¦4jÔÀ•+èÚÉÉX¸…öÖ.Ðmú¬™ž÷!7°ã’´ Ÿä~UFY·èì†6fšÄ¨?JÑmÍ6özªq}”½É+IÐ|šªëþTs]/„uJëÔ©Sööö­ZµzíÿZµjýòË/|‡V.â÷ßÿ׫`ÄÆÆ6kÖ¬sçÎÅ ˜ÊÎÎ^³fM‡ÌO8Ž»pá¡C‡BBBîܹcÞØBÙ'Á¥6eØÑN;JéE)Üh¥¥t§•ž”ÂVzPü®Ãó2}:wllŽOw±ÄžŠ;“Ûø»Rå_¨ ]*÷(Ø@‰JÕ“læ?^vw{nM.óz½JÜv’y½ÞfÓ„5€ÈJx*ÛÅ©Ïë˜)ÉÚ_…7P™¢ðÝwøøc|ðA!¯¾¡ôT.ËÐ_׳,8%¾ I/eþ_Wk ÊÈz‰D4ÐHJwSˆÜ20:í$õ%4€ÚJÏ!“åÜËwÛu‰‹ìóT}™¨¿]…¹VÓh4óçÏ/8³tÑ¢Eƒ®U„_¥oÊÑÑñôéÓ–Ž„°U«V-]ºôرc­[·.f7–eÃÂÂ4ï#“Ézöì9lذ7ß|ÓÍÍ­˜£Å߸ ÎdòÆwíÚµµk×>üßÿ­Q£†-~¡ÊŒbŸ^0ITTÝa¯r«U˜ëõò…6»+¢Œl˜ž” 9)¼ÊfÛ·ã»ï„‡Kµ|˜šê(/Ø^?«eœijÚ(¦idOU·ó.Åbò•Û®]»|||ºvíÊw –DÒmåg4ÇŒ³gχÏ>ûlóæÍC† IMM5¿êää8lذîÝ»+•¥úfoãë‹K—j´je~ºzõêû÷†öïßÿüùóvzŲò‰Ø©‡Úƒ$çÑ–žy½ÞðŸs‡q b½^^)(ðR¶‹Í¹¨c&'k· o 2€±cqêÆŽ-íR}kª½X¤ûœÎ4T%ùXxƒÂørçÎ#GŽT¾J…äf|%§Óé¼gÏ™LÆqÜ‚ vìØ‘ššêîî>qâÄààà§OŸnß¾=00°”¹€EðjÑÂüT$Õ«WïúõëcÇŽå*V;Ë1ª¹È½FPh8öÕïºùË_ª¯ÐõzÍ.›õWWâ"Sy¼DT°§Âަ¶g—gèK~ƒÍÑ4¶mC÷îHHÀ¨QHK+ó.ê˜vgR¬µ©ÕêY³f­_¿žï@,¤ÛÊL§Ó >üСC$‰Z­X¶lÙíÛ·ùå—ÀÀ@…¢Ì-†È‹d¿àììâää´oß¾¯¿þÚ‚?Bòp¿Ñ˜Ãyµ;Ö}õ•y½^óãB×ëÍ~Â^š£2¤ÞªHu‚Ê£¥L´Ý]NsSõs„{…1y2vïÆ§Ÿ–í]ñ id›ÉÈWq®÷Þ{ﯿþ0`Àõë×ùŽÅÒø¾yLX‹Á`èß¿ÿËÿã>>>={öœ1cÆÆÏž=›’’RÖ#ß‹9 å¥Q ÿý·H$¢(jÏž=ú!*–Ûß#k«_Ft¨¡œGJøÇh-ul¼úåWõ,Ëp‘ÌV¿Œ˜Ærž«Yœ¦Cd¦êaÖu½@‡ÅÆr£FqiiexK’‰›¨Ad橺T¦á`óæq@áÿ(г³ã¼¼¸N¸?äŽåXþÆ“]ºÄMžÌµjÅyzr §RqsS§r·o?·[‰C¥Ö­[—÷M%“Éþþûoóö¿ÿþ»GOž<±êOam$ÝVr? ]¹rå„ Ú¶m[èÕ„„„2SçàÀ¦¸¸—_Z±b•JuãÆ¼™™™¡¡¡ÿüóOy{zÁ¸Õ/ãŽY¬%rAð[ÙÅgÓ*˜nYŽ{'AƒÈÌêÑY±FáTæ8.8˜›7Ï2‡ÊÊâ.\àV¯~.ÑvïÎMœÈM˜À ÈùúæooÓ†{ðÀ2ç-«yó8±˜3† âΜáþú‹›1ƒ£iN,ævìÈß­øt˲ìîÝ»³³³Oœ8ѹsg®®®ñññÇÍ›7À¾}ûlóãX I·U ˲> Y¶lÙèÑ£[µjåíí]¶CMs4Í™ O,æêÙ5kÖLJJ2oÙ°a€Q£F•3x!;5%g«_Æïu¶9]L·ÇiY. VÈÌ61ê›rÅzú”S(8€;qÂbÇŒ‰y.ÝîÝ›ÿËr‹å¿äãÃefZì¼¥7o÷Æ…l8¥’‹ÏÝR¦‰@¿üò‹³³s¯^½´Zmhh¨§§gjjª%ƒ¶9ràj¡(ªV­Zýúõ›5kÖŽ;®\¹[¦#Ä\»–Õ(>¸cýúõ?>÷iX˜uOW¨¹sA¿ÔvóñÉ}÷Ї­V­Z娖lFZ·DÙÔupàP¯^1ûxzz+•Ê_ýuÆ 4M¿öÚk.]ºd£(mˆÑãþ.s‘d!~õW>-d¢î X¦ß£.nen~m܈õëñöÛ(võpË(XåµÄ"Ó~Š*ù_ÞRJ%ä/N'ÎÿÁ=<,R%@Z·DÙTc.þþÅïÖ²eËmÛ¶ >|ÆŒþþþ:t8zôè¥K—†j“0m'ú°Q—ÆUk&ªÖ‚L´‘vâ%.²¹iú IÚÚº­ '­¾ÿ>®\Á´iX¿NÉÓ§ùkÕ²À Èo›Ãϯ¸W£¢r4jTþˆ*’n‰²¹<ÖéjöjjjêŒ3>üðÀ€€¡C‡Îš5kÙ²eÆ 3/Ä{ëÖd2eggçääèõúŒŒ N§Õj³²²\\\º”iU—îm×£ìëÿå4ÇYöÐÄþ’e˜ ùÇÛÎG,¸Ž:±æ•Ä£¢°~=V¯.¤»Õ"""põjþÓQ£,pÌž=ѳgyb¾‹Ü¬:t(D•I·D٤ݻ (4ÝþøãAAAAAAíÛ·Ÿ9sæ—_~yçÎàààeË–Ñ4}õêUN'¹×Éj?~ܯ_¿ôôtF“••Å0…—†xíµ×._¾\š&_c’¯™ÜÛˆ«5H¹É¤\gä®”_ Òmò5&æ˜1+špg‹>ñ“g±÷UñƒüC5Å#{FË HОóV*)!Þ8gôë‡{÷àí]æ ÅcY¤¤àôiÌžß6l˜¤ìwÕ¤ó¢=ºTîQ°UÅõh¢šˆ öTvˆËùCmüRJ/ä@åNЩìÚoï2¯û²ž=Q»6pð`îŠÂÉ“x¶hˆ¤¤ #£äÝ”JT¯þÜ;;0 ‚‚,Ó§]Ùð=ñ—¨`¢\]9 ëèÑ÷dæÀ¯¿þzÁ¿·Ú Ȱ,;lØ0nnn^Ϧ(º»»/\¸099¹L‡z°W¿Õ/ãü§ŽãnnÐmõË899Çü’!›5iZ{¡r;œcEfR‘™»²Ë[AÓzŽá(ŠsuåÊXÃãŠ(sÁ0\»vÏ•”2Z®êÉ´iE|¡¾Õ ""8€+j™Ú2•¹¨|(®ª®ßB¼š'4íËqÚðpE©‡þûï¿«W¯þóÏ?M&“‡‡GBB‚U#,”Z­îСí[·zöì9jÔ¨Õ«Wß¾}€L&>|øœ9s6lXšã<9j<õ¾Æ·—¤Ë埯gçOÕÉ)œ®n÷š\ˆí,‹#Ð¥ >ø ÌïEÁ…¤÷î…y€ÿõëhÓy-ÂÂ…–ˆ¸~‘‘%ïæáúª22àìŒÿþCëÖ…ìãëë[£F sÞ­røÎ÷DE²¬I*åN]Hõüâ=zôèã?vppxÀS]×G¹¹¹˜5kÇqçÎëׯEQhšîׯ߱cÇJj¿aGýŒ­~ÇßUsH®ååºÆå 2³eŒZ]Øê:ѧp_]†·“n³³¹5ò_jܘÓÙ¨n÷«¨âé– Ð&Ê âÜ9™²Wâàà`nbò¢S§NkÖ¬0mÚ´þù@³fÍ6nܽpáBWW׫W¯Ž7®~ýúË—/ÏÌÌ|ùæ¡RºTîé“DEiÙs35Œþc¥Ý6Ù‰•¤™7 {=u%ô5=36Ig‰ÚJVñùçhÜC†Xæh* .ÄŽùóŸÛ!<ãÆ!ïVITÜÜpã7¢I|ô¶nE¯^puŦMå'9«WãÔ©ò§râ;ßÉé¥K9àž³3ß”ËÔ©SxzzÆÄÄÜ®Óé¶mÛæÿ¬`–ƒƒÃôéÓ_ØÇ f·úel¯›¹Õ/ãÏ.Y[ý2¶Õθ³EÀ Š*掞qz˜…ÈÌ©ÂýO17@ïÞåÂÃKµ1­[³ó_¥iîܹç^=}šr;x†ëÞûë¯ÜÇr97~<Áq7i'“•·qܹsîZ¼×®ò*iÝDi5óðàZºQE‚µfÍšŽ;º¸¸˜,Ê#“ÉÆŽÜ£G¬¬¬uëÖÕ©SgìØ±·nÝ2ï#QR”,ÉÈŽfE2t^£l8AˆóOª¦†Rú7…˜Â’t}P+*Ëdøï?`Ð Ö‡’O«ÅÅ‹ znch(þþû¹Âß•*÷1ËbìXlߎ»ws·˜G-™K*Ò45Ê]­èÖ-èt8õë@íÚÐëKˆ§DÀq¹ˆ‚Hº%ÊÀÙhP­ˆI·…T*Ý¿ÿ¥K— ­nAÓt``à±cÇ®\¹2fÌ–ewìØÑ¬Y³N:…„„pà¤8˜´»P½‚Tµ­_—(‹ÞJñ 9¼—¤½¬+¼Žï7FýúhÖ Å×Âúë/tìøbñŠ-[ðæ›;6‹¾ú*ÿé£G7mÛæ>U©àæóXàˆ´j•»œÀ¹sðöF``înÂÕÕª•ëçZ²NNèÑýû—ë8•I·D\ðP­æ;òrssspp(~ŸV­Zmß¾=<<|Ê”)J¥òÂ… ýû÷¸c:ɳ«ezk¿Ê½µçœ;I§8Hu%hž˜„xW¡Àñãøýw88àúõ"w:Wø¿ãÇŸÛó£^Ü¡àÇÔË ññ`Y„„`üøÜgÏbÀ€Ü ‹ ƒÐP¼óNy .Nš„ôt;…¢\Ç©”Hº%Ê ãþ}”o¨T…S¿~ýü1!!aÍš5>>>aaaO¯Ø”Ðh»b¢ª%\ëªÉ»)Ä 7 A«f…X]ÀÁ…™3ѪBB¬{.77¤§cãFL˜¿ñìÙüuÌýÕ X7Œ*ޤ[¢ ^«U @­×^+a¿#Gз/ÜÜ A./¼Æk…b®«¬×ëDe]×Ň>¸aþã"Š$¡°×SQOB_×3c’´Blá<< “!-ͺgqr¾}èØ1¿‚ñýûHL„¹öyD–,AHHy{’‰â‘tK”³ÁÀÉ<²¢(+W¢O>ŒôtŒ‰êÕñè‘ⳎôôôáÇ÷ïß?99¹[·n+¼c&J´ÖUÞC!Na¸þ šLATîÞŽŽX»  %ÅŠ'JNÎÈû×_¶kL é–(½ëGH*~Z~ïVíÕ«×ìÙ³u:ÝôéÓ¯_¿þÚKðëÔ©ãܯœ?°|ùrŽã&Nœe.ÛC’˜ÂŸžŠÆRúŽ™(Ð>e†Áî݈Œ|±Œ”e¹¹aÛ6p/†‹‹OD¼€¤[¢´’oß\Tº]ºuëâæÍü-;ƒ¢àãc“èÊ`Ó¦M|yûÎ;›4irâÄ //¯ÐÐеk×*•ÊBpÚhÿÇ>úè£áÇgdd ùä“Aƒݸq#o£yªÏ˜1c233 pãÆ>}ús»®®nÞÇؼys£FnÞ¼9}útkÇO”Gm ý§‡RJae†aS–¡ä7ØœŸÞ}Z-¦LAXßÑ–Å÷Ðh¢âXµŠ¸?.nŸæÍó—&ya]a˜8q"€#FämÉ›ê£R©¶mÛVšƒrrøäÕݾ}{ëÖ­2™léÒ¥x~ªOçÎoݺ5¶`Ý÷¢ùùùÉÌӜΟ7oiРÁ¦M›L›6íÊ•+æÎÎÎýI±vy×^2ÝQjä0,Q)ÈÊ3gâwðÛoå­`L ùÏ$JK÷ø1€ìŠ\z|Μ9 ÃL™2¥V­Zׯ_oݺõºuë$ɲeËN:åççWúCQ«Äýþ{Þ–#F|ðÁ:nÈ!©©©êÖ­«T*>|h~JÇ·Õäý”âT†ëŸ ÉÞ@e©;w¢iS<|ˆà`¾£!,„¤[¢´Ì÷ný*ìÜø“'O:tÈÑÑqîܹ˗/oß¾}xx¸¿¿ÿ… fÍš%•mmŸ{ÕªPÚ×—â IDATˆ€]Š&Rú®‘¨5 .á@l,Z´ÀÛoãÙjËDÅFÒ-QZ*€C½z|ò*8Ž›3g€÷ßÔ¨Q³gÏ6 ³fͺvíZ›6m^á€.díì\ÒÒ””·Q"‘ìÞ½»Zµj‡Z¾|9€V­Z¸zõª…~Âbìi*ØSé&¢ŽhLŸ§ q ²FŽÄ!¨QƒïPK é–(Žã’nÝÀä-)R¡þ|–eG]½zuÎdë$ýä¦0=EwR+¸"-æ¡RÿûZ·Fh(ßÑåS!Ëì¶§b)À(•¢ò •š0ׯ£zuèõ i,\ˆŽ-c‘6oÞ|ïÞ= …Â`0œ:uêÔ©Sw (êÉ“'æ–héÅÔ¬‰[·¤ÿþ `Ë–-!!!!!!-[¶œ7oÞüùóÃÂÂBCC-Z$•Jïß¿Ÿ““cgggÁа”ñö’[æÛ ðíe»zÁ5B|}!“áéS¾ã ʇâ8A „æþ}4h€ºuñàAq»µh¼fâ¹sèÔé¹W;vÄ™3¹µ”.ĪU¸quëZ'â\¦nݺñññy[ªW¯^u뚘{•Ë$%:ºZ½z (ddÄâß~ûí«¯¾ŠŒŒàçç7yòäM›6EGG»»»'%%;w®Ó ¿ B0X``‚&$ÇÔ@B_ö±s¢‹­Tjs,‹GP§ H$(¾ŽªÅÄÄøúúÖ¨QÃ<·ª!­[¢Tþûë¯6@¬ÁP®’Œ æ¯[0b¾üGZ;Ý9r¤{÷î5ÊK®–jeVóóCóæ¸r…»|YÚ­ÛØ±cG޹{÷îo¾ùæÞ½{sçÎuww‰Dééé®^½JÒ­`Ñ@»¢c\Î-;ŒôtŒ‰êÕñè‘ B%Jo©«l€8åތפ0š»Ñ -ÂÆhÔˆïPˆ2"é–(•öuêðmÛ¶\GQ«1|8zôÀâÅ– ‹oE¥úûÀ… ¥zCx8fÏÎ}búœŽ™’¬å;œ|"zô€FƒéÓQÌ_!$Ý%ëÚ¨€;óˆ@988¤7n €;žïXk©.¦z*”õk¶ñ» aUTÞ°ß>ÈŸeFI·DÉ”j5»ZµøD¸ú.] @~å ßVÔJ&Úæ.§€OSu!9õö¿ÿaÄìÞ š|£ ùÏ!Jvaÿ~X°`re”Ѩ(Êtá Âj÷–5T%ùÂYÆï$io f ²L†Ý»Ñ¼9îßnj7!($Ý%£’“òÕ¸¨ìô*ÕŽÌ¿ÿò a] ]d#U’l–ë¯IÒ@åsçв%FÎ]Kš’n‰’µõõàSÁ«-Z•‡‡‡yö-¹}[éQÀfwÅkrQ´‰œ Ñ &á¶m ´l †ïPˆÂtK”L’ž@Z£ßÚk3gÿóOytú4Ú´!S)…Ì|8@ÒmUÔ\*Úã¡óÒô¿«QØI§Ã AhØd\A é–(¹`ò½ .Ø…ï_©ÀrG¶JzK)^â*ã€ñIÚõüT–ËÁq (ܺÅw(¹wK”H‘•@äåÅw ƒ¦Y3¨žJeÙÞ|ù2̶»v-ΞE·nèÓÇqV2ÛIedÉ2LЄy«¼Å<¯D¿~=D"¯P¾A‹©][ôè‘)<\ܨß±TZ­–iÑBuÿ>NB—.|‡CðÀÈ¡g|Î-ÓZ&:ë­TRJñ2W9¼›¤ ã{ 2Ë¢gO´oO–›â I·DqÌ7n%ÞÞ|R‘¨T*I—.´ÇŽñ Á³O¤“¤Zã5±&–ÇHh­ZÁÍ úöå1„*¤[¢8Ƹ8:GG¾©`˜öíxFFòÁ? …?<u%ôU=3Ž×Ê*Œ= ÕòGUEÒ-Qœ>­ZhÒµ+ßT0½g΄‹‹SVbbøŽÅŠL&ÓÇ?~œžž®'uÇŠæBS!^J'šú3Ǹ8Ï_Ã`Ñ"œ8A&ñ€Œ8%Š#NK óõå; F®PpÔáÃÙ¡¡ö“'ó޵ˆD¢)S¦+p‹ÚÙÙY&“)•J™Lfoo¯T*U*UPPq ¿„Þã¡è› ù2]__JRIx C$ºu¸~S¦ðrþ*¤[¢8— âŒF2Vª¬þˆÄüö[£Ê›n)ŠÚ²eKÓ¦M3ž-‡œžžþònNdÒ6 —R¼ÊUþQŠnb’¶¶˜‹x £S'tê“ GŽ wo^B¨¢Hº%Šã Ó׬Éw ¸K\»æa.€\yùøø¬_¿~ôèÑ2™L¯×S5pàÀ>úÈÞÞ^¯×«ÕjµZMÓä¦U®ŽÒûc–aP‚&ÌÇ®†˜Ÿß à W¯âÒ%¼ö/!TE¤f2Q,//$$p±±™ TVZ-œa4"- •}¬ÙèÑ£ƒ‚‚¼½½SSSu:X,~÷Ýw/^ìééÉwh‚cäðf¼æ„ÖÔB&:_]iGóSQù³Ï‚_~A§N¶;)©™LE`Y$'ƒ¢(ww¾C©€ ¦E °löÑ£|‡bu?üðƒ¯¯o\\ÜŒ3&OžÌ²ìÿۻ󰦮íoàëd$džAQAfqÅ«ôjì½oQkKp.½W µV°“¡¾µb[5Á¶Šö¶«Õ¢Á PTdpFeAH™~ÄK‡¢$Ù¬Ï_!Äs¾}ž¶Ë}²ö^B¡ÐÙÙ966öÑ£G¤Óõ,L Rl8ƒ™´‹yD˜ÔVÜøx(,Ôj­EXnÑsggƒ\þˆÁ&™¶ŽÞnoM ÜùåÒA4ÎØØøÇ¤Ñh7nŒŒŒ<{öì¤I“ZZZÜÜÜ„B¡L&#±1£Ql¹¦4j_‹l-¡Få>}€¢ ) ^{ Õ,·è¹ËË Å"¤·bŒÖú±ûvÒ¤IË—/—J¥óçÏ÷ðð8zôhFFÆ!CîÝ»åííššJ:câʤýjÃaPðEƒd÷#2'*ËåðÅpø0ìßOäþzË-z.ÿÀÆÇ‡tÞjÖ† @QæååÐÖF:‹6$$$xyy¯Y³‚‚‚.\¸’’Ò¿ÿÒÒÒððð1cÆäææ’ŽÙSs›Ì ”‘µâ¼V L66n„Ÿ~‚Y³´s}„å=_M °Hçèµ,,Zœ@,n9uŠtm`³ÙÉÉÉ,kÓ¦MÇV\\ÌçósssÇŽ~ýúuÒa{„¥Æ¬¥Æ¬V%̪Ý&q¢ò¬Yð¯H8Y °Ü¢')•P_¯zùÇ÷ßÀ%<Ѽ2Åb¸ýóϤƒh‰¯¯ï| P(6lØÐþ&—ˉ‰¹víZLL ‹ÅJMMuwwŠŠªÅ³¸- ^ã2ªåÊi÷EM$NT®©WW˜1êê´sý‚åupþ<  ÿú—ê'ª¶äff›‘¡ZcOš¶ú´˜[»v-ŸÏß³gO§÷ÍÍÍù|~aaaXX˜T* …®®® ­­­Dröt€Ÿ­9ž,Zq›âÍj±öŸ)[Y·7¸ºâ܇ûnQ `o ”—ÃÀÀãAR’ìÛoK—Âýûàît:\¼ŽŽ¤ƒöàâVVPU™–=ÐÙ³gW­Z•••ŽŽŽkÖ¬y÷Ýwõù4ŒRÅÈ»-ureŒ ›oÎÖòÝ¡o_müë‰ûnúSSxóMP(@(¨®†ÀòåÐØãÆa­}9Îέ¦¦PS#-)!¥9räÉ“'322¼¼¼îܹ5räÈcÇŽ‘ÎEÌ&m¯ —EAÂCIR“¶ëŒA"¯¿†?Öòõ –[ô¤ÈH€; ­­ =j( ÒÒà·ßÀÐ6o&¯:¥PÀÍÝ»Iéq‚‚‚ Íùóç'Ož|éÒ%Ò¹È4 oµäÀÒºÖbmoS¾~V­‚„¸{WËwÖ#XnÑ“üýÁË ª«aÿ~“¶6èkoË–ÄÅáÒö°&N½Ù}û² Ç«¨¨àóùFFF™™™Ã† ¿uëéh,4b¾gÌ’*aNµøšT«ÊðÅpäài­šƒå=åÝw’’p¹`š ·nÁ!M8Xï4nõjè{ù2é =WŸ>}bbbJKKy<FKMMõððˆmll$MÛ¾²0˜ÁeÔË•¡U¢Fí6*ðL˜pïž6o«G°U =åÁƒÇ SJ%€BR)dgØ1¤“õJr‰DalÌH”÷ïÓðÈþ¿SZZºvíZÕTæææ«V­ŠŽŽf³µÝ=DÐ#…rÌÝ–Â6E—‘fËÕæ”¾Œ xóM˜<RR4r}l•BèIff0{6(• mkƒ¶6xûm¬µ¯ŒÎfçÓhÀm=8<¹ûÜÜÜRRRrssêëëccc}||RSSõga`D£Ør­èÔŸ"YL½VwIyyDuu !s³ŽÃr‹žåí·@ÀT(ÀÔÖ¯'¨w3 ›k×Hé5üýýO:•’’2hР²²²ððpÿ,½9úȉAû͆˦ેm-6*ÛÚBI ;úô4A{°Ü¢g™4  zü_Ü_àëßeËÀ ?ŸtÞ„¢¨°°°’’@`eeuæÌ™ñãÇ‘ަ c èK,¯k=®ÅFeGGhh€uëàâE­ÝS_`¹EÏBQÒùóFtš^¯ÅÛ[AQ²3g@$"¥—a2™<¯´´4&&ÆÀÀ 33Ó××7**ªººšt4›oÄ\iÂ’*aN•¸B‹Ê_~ ññ¸Wý°Ü¢g[{ýº`ßÔ© Çgý¨ ׯ¦ˆNg(•UüA:K¯djjÊçóËËËÛg×4Hf×'˜¼Þ‡ñ@¡ ½/z¨­Få÷߇™3!>^;wÓ#øRôl÷•ÊéROOÒAtEQÜ)SÀ¼´”t–^ÌÁÁA \ºtiúôéªÙõîîîB¡P®»ãÑi?Yq|XôR©bnµX¦•‚keûöŸ<|¨Ûé,·èÙvìØ‘.‘ÌÂI˜j2hÞ<`ž=K:H¯çéé™–––‘‘1tèлwïêüìzCuÀ–cM§Žˆd+µØ¨ööpá‚Ön¨û°Ü¢gkiia±XL&“tQëê ÍGŽ€‚ÀXSÝtþüù””''§’’’ððpÕ4{Ò¹4¢?ƒ¶×†Ë¦ ±±m«¶•A,†ÌLíÜM/`¹EÏæèèÈårHÑ}ÝÝoQ”¡LÖ˜›K:‹F(ŠãǯX±ÂÝÝÝÈÈèÈ‘#ª÷=z´páB“µkת÷Žf×=ztøðáº:»>À€ždÉ€÷êZj¥Q96Ξ…>Эô–[ô R©d2™‰‰ é,:‚Íf3'LãÂBÒY4B$‰Åâèèh''§æææÍ›7€D"™5kÖÍ›7›››+4sj4‡ÃÑ“ÙõFÌX¶T áUâ2Í7*ÛØÀðápë|ÿ½¦o¥7”!íØ²E ÿç?IçЬ½{÷€¡¡¡L&[¾|ù‘#G”Jemmm[[›¦o}óæÍˆˆŠ¢àÍÌb±XÓ7Õ&¹R9ó~ T4ºÞzô@®Ðô핆†J:]Y^®ž ªÎntttTÏåz\Ý¢gÉd:¿ÅBûnØÛ@ÍÞ½¤ƒhÖ¸qã(ŠjnnÞ´i“‰‰Ipp0XXXh¡ ÿþÉÉɪ1bcc, ºò}9 à¿ÖÜálúU©bn•Æ•ûö…yóÚOtEÝ…# Ð3¤§§‡„„L™2%==tÝñ¨©Ijll ½v9p é8äááQRR2xðàË—/“š.™™ùïÿ»°°üüü6lØ0qâD"IÔîžL9ònó]™r©1ë[ Òq^Ž(@¨³‡r¹\kkkÒAtŠQß¾ÌÀ@Ѓí@0uêT‚“|TÊí³ë'Mš|Y'Æ Ú1¨ý6\.E}רö]£Æ•oÜââ4}݇å=Ãܹs[ZZ’““IÑ5F!! 9vŒtÍrss€K—.‘Ñqv}ß¾}U@Λ7ï^ïèêǦï°2 Þ«k=$Òl£òÇ”‰‰xiwa¹EÏ ‰$8‚K.ÀÝ_%DƒêëëüñG8wÅ,Õìúk×®­X±‚F£íÚµËÅÅEfׇ2?2eËþY-.jÓà—Ó¾¾yyÀåjî&zË-z†E‹ìܹ“t]cÚп© zùÿë_`Ù²eß~û­£££X,Îï1C,,, ÃÂÂD"QBB AƒÚÚ´7ÞNí>1c¿iÈlR(C«Dur vá|ð¸»Ã¸Àí,·èh4—˵¹{êf3`€rØ0:œ>M:‹Fü÷¿ÿõðð7nÜøñãàĉª÷322HÆúŸöÙõcÆŒQÍ®WÙK;F)€¬8#ÙôRÅU¢6MþC|þ9  Û·kð:Ë-z†;v´´´L›6tÄž<^,õ/¥Z[ÁÞ<€œx•+à1=ÁØØ¸²²k­æ(àþž=¤ƒ ¿¨f×_¾|yÆŒÍÍÍ nnn½kvýZSö¿ ™ÊÐû¢Z 4*Àа|9ôë§ökë,·¨3‘HTUU…=4çhk+ÜÓ݉轗‡‡Çü‘‘‘áëëÛëf×Sß[qFÐoÊoT‰$ø/8.6oõ_Y`¹EÍÍ ™°¨ûT³ëKKKUsÚg×߸qƒt´¿aC§ØpúШ¤_=Tÿ!R)ìÝ ÉÉЛ!Ë-êì­·Þª««Û²e é º¬ÍÏ*ù…tô",ë½÷Þë8»ÞÍÍí½÷Þ{øð!éh/2”MßeÅ¡|Pßz EÍÊC‡Â®]på °Xê½°îÃr‹:«©©©®®îÕ‡Ûõ|'e2¨l?<ù¿ÿ…3à÷ßIfBÏaffÆçóËÊÊ"""¤RéæÍ›U@¶¶¶’Žö\³ú0>1c+Þª_nSs·×[o…‚®ÌÖ,·¨³¨¨(›ƒ:tìQd9ktüúöÈ8xÏìéÉúõë§š]?a„ÄÆÆººª–u¼ IDATºöäÙõ«MÙo1)”¯ßר»Q9"||àÈõ^UÇa¹E±X, [[[ÒAtέ[0|8œ9Cß~¸\“êjPm¸:y`üx¢ùÐß1bÄñãÇ322¼½½oß¾5jÔ¨ãÇ“Îõ @’%Ç߀~K¦˜¥îFeoo01Á¿¾<æ!mY¾¾ýúõƒ³gÁÚºeÔ¨>gÏ^߸qàܹ`oÆÆP_t:锨K ÅîÝ»cccïß¿AAA_}õ•é\UË•#+[nËóŒ˜;­8꺬j4ÐËŽäÃc.zÂ7H§ÐE6€¿?ܾ ¯½"Ñi<^ÚŽƒµ¶¡ÑhóæÍ+//ï4»^U}{k:uØ–Û—F%?’&è×.\€ ,ÿñðij‚S§ ÇC/ïéÙõÎÎα±±MMM¤£ýŃEûÅšCX]/Ù¯¾FåË—aêTX¹ZZÔuI‡å=ááÇýû÷wvv&DGY[ÃþýЧ¤¦úˆÅ@§_»öxu‹å¶×RÍ®¿råJÇÙõ‰‰‰2™F¦¼‚i\ÆæªFåKjjT2f΄èhè=Ç\†ßÝ"¤uûöÁœ9 ²²âVUE› ›M:ê®Ó§O¯ZµêÔ©Sàêêú駟Ι3‡¢(Ò¹xµ­IMmv ꬽ¡=ƒ@$üî¡¿444”––677“¢ÓfÍ‚uë@¡`×Ô(•0r$ÖZÝ0zôèììì8;;_½z5<<< @U}‰ûÎÂ`‡qO¦œY%©i¡õûï0~<œ>­–‹é8,·è {÷îuww_±bé ºî£`ölzû–ÍW›g†zªÐÐÐââb@`mm}úôéÀÀÀÐÐÐ Ògv2)ØcÍqfÒò%ò5­j©·gÎ@V6Lu –[ôƒ1pàÀ~8aKÓ( vî_ßÇ?â·:G5»¾¢¢¢}v½‡‡ñÙõætê€ ×˜F¥6K¿hPC£2Û¶ÁW_uÿJº¿»Eˆœ;wÄÞÞMM×ÏäçG: Ò”»wï~òÉ'í³ëÿóŸÿÄÄÄp8jÛû²ÒE²é÷E €Ÿ­9s ™j¹f]XXüÍgð»[„þríÚµÊÊJ©TJ:ˆ~ptüÔßÿ”R™™ŸO: Ò {{{Õìú°°°æææuëÖ¹¸¸œ]?•ËøÒÜ@ ðvøœ¤»**ÀË &MRK4]†å=!**ÊÑÑñĉ¤ƒè‹©±±uß~;sæLÒAÆyxx¤¤¤tœ]ïããCjvý¿MXQ}Yb%̬UʺuìsÿþP_"ô°>z,·è æææ¶¶¶666¤ƒè‹ñãÇÏZº§ ë   óçÏ«fׇ‡‡h?É7“8Œ{2å?ªÄÝiTf2!/ÊËÏY1,·è ¿þúë½{÷¼½½IÑ#+W®tww¿ƒÇ½ë Š¢:ήÏÌÌôóóÓþìz&©6&í‚D>¿{ÊNNÐÚ Éɀǿ¾–[ô…BQXXX£Ú Š´¥´´´´´4;;›t¤Ug׳Ùl"³ëÍhÔ[® ÚÓ,ý¤{ÊÿúÌŸ?ÿüøÇôt4bcÕRg`¹E©««óñññôô$D¿ÄÇÇŸ?~îܹ¤ƒ T³ë¯^½Êãñd2™ög×»1i¿Zs¬{ ù¹ùÕ{$çÎ…Ñ£ÁÁáñååpý:46ª'¤nÀr‹þÒÒÒ2tèÐaÆ‘¢_†>lØ0:ŽÒcýúõgΜ™8qbûìúäädílÔœÂe|en XX#>ÓúrÊR)¨þbðæ›—¯¿þø}ÕNÜÀß–[ô—¤§§“¢_”Jexx¸••U#®ôÛðáÃ;–‘‘áããsûöíùóç5J;ÛV³÷eµ*aV•èN—•årˆˆ€éÓª«ƒÄDض àæM''¤í¥°Ü¢¿Ô××ÖÖÖ’¢_(Šº{÷nmmí¹sçHgAäìܹÓÖÖöܹs'N ¾|ù²¦ï»ÙÂ`2‡q_®üG•¸EÑ¥Uõ;pâ;Ó¦Á£GpëDGC\H¥pë–Û'a¹EÙ½{·ÏgŸ}F:ˆÞÙ²eË;w‚‚‚HA=‚jv}EE…6g×3(Hµá fÒ $òy5­]Yá:9ÁéÓ0hdgÃøñп?,[[¶EªÉËmGXnÑ_Øl¶‡‡‡‹‹ é zgÈ!ø0uÄårU³ëcbb Æ®]»\\\4:»Þ”F°åšÒ¨½-Òø]jTvr‚ãÇÁÅ `Ü8X½fωjkÁÀpGxf2BäI$’aÆ]¿~½¡¡ÁÀÀ€tÔ㔕•­Y³fÏž=J¥ÒÂÂbÍš5K—.e0š¸W–X|¿Eª„]Öœÿ×µ•««!8 ÁÕ&M‚?þ€ÊJpu…ÒÒ'>†g&#ôXyyùÕ«WÅb1é z‡Íf3™L&“I|FꙜ’’’——XWWíå奡 Çqè[,8J€wkħ»Ö¨lm 'Oˆpõ*ìÜ ••ø$ù)XnÑ_Þzë-77·K—.‘¢<ØÐÐàååE:ê¹F•••uàÀÕìzMÌ®§/s¹ñãFåÛ]kT65…C‡À×D"Pmjëß_í¹z7,·è/ÎÎÎîîî¶xò) ööö2™¬¨¨ˆtÔÓ…††izvý×Ó¹Œ*¹òUâæ®5*[XÀ±c0z4¨a¹íË-P(öööaaaxx/õõõ&&&cÆŒQ(º5žéƒöÙõ|>ßÐа}v½O`¥üךãÅ¢]”È#jÄ]ü—ÒÄŽñãðaòÓ”H復¦r¹ÜŽÿV˜ššfgg“Î¥wœ]]]ïܹC:êM*++y<žêT2CCø¸8‘H¤®‹_o“[Þh‚ŠÆë[»þ§$å̙ʜœÎï«:¤Õ¯wÁÎd}÷믿þóŸÿ|ú_–““3zôh"©ôS[[‹Å"õJ%%%qqqªæ)‡?þøwÞQËÉ Ù­ò {-mJH²ä¼Û·KÊÐÚ 2>ñ&v&#½öÎ;ï<ó¯\ …",,Lûyô‹Åª©©Á³¥Ð+pwwOIIÉÌÌ6lXee¥jv}ZZZ÷¯h@ßfÉ€¥uâ“⮞¨l`йÖ",·zíäÉ“-ªÓNŸ¥²²‡ñiSYY™µµõo¼A:ê­&OžœŸŸŸ’’2pàÀâââÐÐPµÌ®Ûˆù¾ «M sªEפØ[ðаÜêµÜÜÜWZÚäâââäääååÕÜÜL: ê­T³ëKJJ¥¥effæðáû?»þÿ›„öaÔÉ•¯W‰»Ö¨Œ:Ár«×8΋?Щ… iEQ7nÜ8|ø°!>†CÝÃb±x<ÞÕ«WcbbX,V÷g×Ó~²âx³hÅmŠVwù™2êË­^›>}ú ~KQ”¿¿¿Ö H$§N:|ø0é H˜ššòùü²²²N³ë%’.‡Ü‰:`˵¢S‡E²ë[ÕžVça¹Õk...ýž?zÔ¨Qx~¯–FGG“‚t‡£££@ 8{ölûìúÁƒ¿Úìz'm¯ —MÁ†‡m¦6M¤ÕaXnõ]ffæ37ŸãKû† âïï?mÚ4¹×!uòóóSÍ®2dHûìú“'O¾ìuÆÐ–XV×z\,Ó@R…åVß¹¸¸”––úùùµOa2™&L¸~ýº‰‰ ÙlzˆÉdææænÚ´I-;&ê$((èÂ… )))ýû÷?wîÜ„ ‚ƒƒ _ê"ó˜«LXR%„U‹+°Q¹Ëð˜ ô—ºº:fffF:ˆ^{øðáñãÇ Fhh(é,Hg‰D¢o¾ùfýúõ cáÂ…ñññ]?/]ðF•h‹ÌE˵ïcB£ºò§ð˜ „³°°ÀZK\~~þo¼ñÙgŸ‘‚tYÇÙõt:](¾ÔìzÀn+Ž‹^Ò¦x³Z,ÃU[`¹E¨g5jTHHÈìÙ³IAºÏÜÜœÏç_¾|9,,L$%$$ 4(11Q&ûû/e iÔ[Ž5JÉ>x€Ê&#„‚3gÎ|ðÁYYYàêêúé§Ÿvå×ÜVù¤{-%lµ4XÔ÷oNüƇÉ¡ž¥¢¢býúõ¿üò é H¨•322<==U³ërrr^ü§ èÉV `E]ë1lT~!,·õ8………«W¯Þ¾};é H¼¼ÀÀÀðððk×®½à„2?4eK•V%.ÇFåçÃr‹P3f̘+V¬X±‚t¤:Í®OMMuwwñìúÏÌØs ™ÊÐû¢‡x¢òs`¹íõæÍ›Guàçç·xñb###‹åèèøÖ[o‘މ^‚••Ubbâ믿N:Ò_}úô‰‰‰)--åñx …B(4(>>^,?ýa àG+Î6ýªT^…Êφå¶×Û¾}ûŽ;Ú,))áp8ñññ?ýôÓðáÃ+++U/Ž=J.#zi§NZ°`Á®]»HAzÍÎÎN †……577¯[·nðàÁB¡ðéSÏ8ünõgPbÙ¿ñDågR¢Þ¯ã˜}:î¾E=ÍÓ³ë=<s®-ê±^ýõ””>ŸO:BÏ¥š]æÌ™I“&Õ××ÇÆÆººº&''€òw[®ƒ–%–/©{ÆÞ!=„åVǵ?Þ+++‚IÐËêß¿XX˜ é ý ??¿£Gªf×ߺuK5»¾ìTÖNõ}“ô›Æ6ÒÉÃr«ã:¶0øúú¶¿~ûí·}}}§OŸ4eÊì¢ê™6nÜèì윚šJ:B¯}v½“““jvý3B>k­¡¼_×zP¤ïÊXnuÜ©S§T/h4ÚÌ™3Ûß/++;wîÜÁƒ333ýýý§L™RQQA(#z.‘HtíÚµÓ§O“‚P—Ðh´°°°¢¢">Ÿollœ™™¹ÊÇmXÎ9À¿ªÅW•tÒIÂr«Ë²³³Ïž=«zýÎ;ïôëׯýWqqq CõúÍ7߉DGŽ!½Ð‚ ._¾¼aÃÒAz f×ç¿=—qôp“\‘Ýª× \,·ºæÆS§N]¼xqddäôéÓUoN˜0áë¯¿îø±)S¦´¿–J¥ðd3ê!¼½½•J¥BûQ/£š]ŸŸŸÿZHˆ,z!¼¶-ð¹ûÈóòòÖ®]kffFQÔÓßžœ={ö³Ï>kÿQ*•ººº:99•””h*½`¹Õ5&&&b±xÏž=;vì Óé[·nÍÌÌìÓ§ÏóþHAA“É ÖfNÔ …bìØ±l6ÛÝÝ}Þ¼y¤!ôr¼¼¼<˜þû>ëÒË/˜)äïïÿÉ'ŸDEEÀáÇ;þJ&“ñx¼Žm(t:]©TÞºukÏž= ®~ Òš988deeuýóR©ô믿^³fƒƒƒæR¡WpôèÑÐÐPÕ–²²²²²²]»v¹ººæçç’N‡PWí߿ٲeÕÕÕ,kÆŒ³gÏ~Þ'UǨuš`öí·ß^ºtÉÑѱý¶oß>__ßAƒi.¶Úa¹Õ5­­/7‹cÅŠ£Gþøã5”½šû÷„tÜ6­rõêÕ‘#GI…ÐK¹uëÖ’%KT§µO™2eëÖ­|Áç=== ã4û›7o644@uuuÇOzxxØÙÙ͘1C#¹5&ëš§c=L&‹ŒŒ´²²Ú¶mEQM…^Ö¼y󞮵*%%%Ôr„^Š\.OHHððð8t襥eJJJzzú‹k-899QU__/‰TïlÞ¼yéÒ¥ðT¹ÍÊÊzóÍ7ûöí«¡üš€åVO577‡‡‡­[·Žtô /Þü³mÛ6­%Aèeåçç><66V,«NW ëÊd³ÙªÓx*++ %%% ÀÒÒ’Á`t,·J¥rãÆ±±±ʯ!Xn{=©TZZZÚþcKKKaa¡ªÙøyêëëÇïããcllüçÿ\¸pAóaQW©¾²}ž;wîh- B]×ÜÜüÞ{ïùûû_¼xÑÕÕõøñãÀÔÔ´ëW°´´€{÷î566þôÓOsæÌ¡(ÊÜÜ\"‘´Ÿ‘÷ÝwßÍœ9ÓÄÄD#ÿ ƒßÝözQQQ?þøcû•••>>>/h˜*))¹páB§ú:}úô´´4 E/ƒÁ`¼à{Þõ é‰ôôôÅ‹߸qƒÅbÅÅÅÅÄļÂöB ¨­­ýð×/_®zÓÊʪºººººÚØØøÊ•+‡îß§`¹íõ~øá‡~øá¥þÈØ±c•JÒÑ£ 0 ãC‹N¦M›¦Í0½XmmíÒ¥KUûeGŽ™””äããój—RuÝ:tèÖ­[AAAª7UO˜«««ííí,XÐK§RâÃd„z¢/¿üòy¿âr¹«V­Òf„žG©T …BWW×ÔÔT###@——÷ʵŒŒŒ`ÇŽñññíoªž0WWWóx¼E‹9;;w;8Xnê‰BCCcbbž~ŸÍf;v¬ýN„ºzõêĉ£¢¢fÍšUZZÊãñh´n•.— 'N7n\û›ªÕíúõëårù»ï¾ÛÍØ¤`¹E¨‡âóùééé^^^}úôa2™æææS¦L¹}ûö¨Q£HGCú®­­->>Þ××÷äÉ“öööØ»w¯]÷¯¬*·—¶ð¿Õ­X, …Ý¿)øwd„z®)S¦’NÐΜ9Ããñ._¾L£ÑV¬X±nÝ:56 ›˜˜„„„t\Ú€•••µµuZZZ¯n¤°e!„PWLFˆ€›7o¶¿~æÿòNœ81|øpÕ¡ðu_rr²§§ç®]»¸\î¦M›NŸ>µVËpu‹§NR½ Ñh3gÎìø«ëׯóùü¦¦¦óçÏ“ˆ†tÍ­[·–,Y¢Úo6eÊ”­[·8t(}„«[„´-;;ûìÙ³ª×ï¼óN¿~ý:þÖÔÔtÛ¶mñññ’!Ý"—Ë<<<:dii™’’’žžŽµ–\Ý"¤ 7nܘ:uêÀe2Ù¯¿þªzs„ _ýu§Ošššj=ÒAùùù<¯  €¢(·~ýz333Ò¡ô–[„´ÁÄÄD,ïÙ³çádž††‘‘‘t:t4¤kZZZV¯^½eË™L6xð`@0aÂÒ¡–[„´ÂÁÁ!++‹t ¤ûŽ9²xñâëׯ3™Ì¸¸¸˜˜˜Ž›¼AXnÒ†ÖÖVÒŽ«­­]ºtijj*Œ9R(2„t(ôl•BHär9éHg)•J¡Pèêêšššjhh(òòò°Öö4¸ºE¡^¬¬¬ŒÇ㌵¶ÇÂñòiÄÂ… üñÇNoþmÃÔéÓ§÷ïß_^^þÛo¿ùúúNš4©}>.B*gÏžŒŒ¼|ù2EQ‘‘‘ &&&¤C¡Ár‹B½É£GV®\¹}ûv…Báææ& I‡B&#„P¯±oß>www¡PÈ`0âââ °ÖöØ*…B½ÀÝ»w-Z¤šZ1zôh¡PèííM:z ¸ºE¡MµÏÇËË+--­oß¾ 77km¯ƒ«[„ê¹JKKy<^vv6Ìž=û›o¾±µµ% ½ \Ý"„PO¤Úçãëë›íààpàÀ={ö`­í½°3!„zœ¼¼<wåʶlÙ²O>ùÄØØ˜t(Ô-ø0!„z¦¦¦U«V%%%)•J¡P8fÌÒ¡àÃd„ê)öìÙ£ÚJËb±ø|þÅ‹±Öê \Ý"„ywîÜY²d‰jŸÏ¤I“³³3éPHpu‹B$)ŠÄÄDooï´´4ssó;wfffb­Õ=¸ºE!bŠŠŠ¢¢¢rrr ""âË/¿´±±! i®nBˆ‰Dëë뛓“Ó¯_¿´´´ääd¬µ: 7!„¶;v,**ª¢¢‚N§¯\¹ríÚµ\.—t(¤Yø0!„´§¾¾þý÷ßß½{·R©ôóóKJJòõõ% i>LF!-INNöòòÚµk—ËÝ´iÓéÓ§±Öê\Ý"„ÆÝ¾}{É’%€àààmÛ¶ 8t(¤U¸ºE! ’Ëå îîî´°°HII9räÖZ=„«[„Ò”óçÏGFFÇ[¿~½™™éPˆ ,·!¤~---«W¯Þ²e‹L&srrÚºukHHéPˆ$|˜ŒBj–‘‘áãã³yófˆ‰‰)..ÆZ‹pu‹BjSWW·dÉ’ÔÔT1bDRRÒ!CH‡B=®nBH=„B¡««kjjª¡¡á¦M›rss±Ö¢v¸ºE¡î*++‹ŠŠ:qâ„„„lÙ²eÀ€¤C¡žW·!ôê¤Ri||üСCOœ8aee•’’røða¬µèixf2B½¢sçÎEFF^ºt‰¢¨ÈÈH>ŸojjJ:ê¡ða2B½´æææ>úHµÏÇÍÍM Œ7Žt(Ô£áê!„^Οþ¹xñâ›7o²X¬?ü0&&†Ãá…z:\Ý"„PWÕÔÔ,[¶LµÏgôèÑB¡ÐÛÛ›t(Ô;`«Bý=¥RÙ¾ÏÇÈÈH äää`­E]‡«[„ú¥¥¥QQQYYY0{öìÍ›7ÛÙÙ‘…z\Ý"„ÐsµµµÅÇÇûúúfee9888p`Ïž=XkÑ+ÀV)„z¶Ó§Oóx¼ÂÂB¶lÙ²O>ùÄØØ˜t(Ô[áÃd„ꬩ©iÕªUIIIJ¥ÒÃÃC Œ;–t(Ô»áÃd„zÂo¿ýæîî. Y,ŸÏ¿xñ"ÖZÔ}¸ºE¡Ç*++/^œ––'N...¤C!«[„…B‘˜˜èåå•––fff¶sçΣGb­Ej„å!¤UçÏŸ_·nÝo¼1xð`OOO¹\Þþ«ŒŒ ccãùóçk9Rqqñ¸q㢣£#""ŠŠŠæÍ›GQ”–c ݆å!¤U¶¶¶sçÎuww/~rÐZIDAT///..NOOoÿUSSSSSSrrrEE…vÂH$’ØØØ¡C‡æääôë×ï?þHNN¶±±ÑÎÝ‘^Ár‹Ò*;;;77·Ï?ÿ|æÌ™ðÓO?µÿjöìÙ‰‰‰`ff¦…$ÇŽóööNHHP(111ÅÅÅ3fÌÐÂ}‘~Â}·!2:4}útccãÚÚZ&“©zS*•Ž1ââÅ‹½õƒ¢££wïÞ­T*‡ –””4lØ0Þ!\Ý"„È 222jll|ØÒÒ2%%åÏ?ÿÄZ‹z\Ý"„ˆijjúý÷ßSSS»s‘sçÎEFF^ºt‰¢(ÇçóMMMÕ•!uÁr‹"C©TFGGóùüö“_VssóG}¤Úçãêê*º¹JFHsða2BH{ªªª¾ÿþû¦¦&X½zõܹs_y£mzzºÏæÍ›i4Z\\\AAÖZÔ“áD „ö,\¸ðÇ´¶¶vww_¼xqxxø+\¤¦¦fÙ²eªGУF …>>>êNŠšáê!¤=¯½öš‰‰I¿~ý>ÿüóW¨µJ¥R(º¹¹¥¦¦ ‚ÜÜ\¬µ¨WÀÕ-B¨w¸zõ*ÇËÊÊ€7Þxã›o¾±³³# ¡®ÂÕ-B¨§kkk‹÷õõÍÊʲ··?pàÀo¿ý†µõ.¸ºEõhgΜ‰ŒŒ,,,¤ÑhË–-[·n‰‰ éP½4Ü„ê¡=z´råÊíÛ·+ www¡P8vìXÒ¡zEø0!ÔíÝ»×ÍÍM(2™L>ŸéÒ%¬µ¨WÃÕ-B¨g©¬¬\¼xqZZLœ8Q ¸¸¸…Pwáê!ÔS(ŠÄÄDooï´´433³;w=zk-Ò ¸ºEiÕ‡~Èd2ccc;  -))áñx§N€°°°ÄÄD[[[BR?ìLFiÏåË—ýüü(Š*((ðôôT½)‘Hâââ6nÜ(•J¿ûî»ÐÐP²9R;|˜ŒÒ…BñÎ;ïÈd²ÿüç?íµöøñãÞÞÞ …bÅŠW®\ÁZ‹t®nBZ’””ÄãñœœœŠŠŠ¸\££wïÞ­T*===…Ba@@éŒi ®nBÚP[[ 6làr¹ÉÉÉžžž»víb³Ù|>¿  k-ÒmØ*…Ò†Õ«W?xð`Ú´i£F Uíó Ú¶mÛ AƒH§CHã°Ü"„4.//ï‡~`³Ù~~~^^^MMMæææ7nŒˆˆ (Št:„´¿»Ei–B¡ð÷÷?{ö¬Ý½{÷ ""bÆ ÖÖÖ¤£!¤=XnBš%-ZÄf³%‰™™Ùܹsmllªªª*++ïß¿ïÞ=‹uãÆ Ò1Ò,,·! ª««suu}ðàÁ >Ãd2[[[i4ìÜDº ¿»EiªC ŒííííþÇÖÖÖÞÞÞÖÖÖÁÁÁÆÆk-Òy¸ºEiŠR©ÌÍ͵²²²··ïtd#Búæÿj;ÒHîIEND®B`‚opengv/doc/addons/images/central.png0000664016516101651610000001766313344612246016444 0ustar dimadima‰PNG  IHDRþä7¹ûbKGDÿÿÿ ½§“hIDATxœíyXTuÛÇ¿3À€È* ¸’2š`.=âR˜ú¦i¹¼öTZ¹ZAiEW¦d+>©P¶)ù¦åR¸ä†Oй”© …kŠÈ.(‹ìÈÌÜïg†ÙÏ,¿ÏÅå5œ9Ëç{î¹ÏýÛDÃöò-€ÁàfýVÄÇó­€a ˜õ[rïÞz 11|ë`fý–dgC*Åþƒwßå[ ø0ë·$3SþâÓO±d ¯RÆ…Y¿%×®5¿ŽGl,RÆ…Y¿%YY-~ýà¼ù&ORÆ…Y¿%Š„GÁš5xë->¤0Œ ³~KT¢>ÇêÕxûm“KakÍm¦ª îîjß‹cEOk‚E}%”Ÿq[óÎ;øì3SIa{¾˜­ýþý€k×› ‰o¿ ;;Vô´XÔWB9êGEA @q1vïÆõ먫Cf&öìD‚ìlþ$2 ‹úJ(žqW®ÄŠøã¤§ãðaL› €xÕÇ0$,ê+ÁYÿ£°b̘»vñ)‰a4X…G ww,[Ö\ÇÌÊB` ÜÝQRGG^•1 ‹ú÷¹uKµ~?`‚ƒq÷.~û?Y cÁ¬,\¨º‘å<Ö KxÚåòe //ÃÁo5 C¢~»C,FYŽç[ ÃÀ0ëwËy¬–ðtDz:BCѵ+Š‹aÏšA¬õ;"$¸s'Oò-…aH˜õ5€å<ÖKx4 - #F {wBÈ‚…•À>H 6 ½{ãÖ-œ>Í·†Á`Ö×Ó§,ç±*˜õ5ƒK÷wìË­f}Íxäøù¡ gÏò-…a˜õ5C(ÄÓO,籘õ5†å<Ö+njŒLãï¿·†¾°¨¯1B!¦NXÎc%0ëkƒ"çaX>,áщ¾¾¸}—.!8˜o5 ½`Q_ìíñä“°s'ßRú¬¯%¬+›µÀ-ij‚**põ*Äb¾Õ0t‡E}-qpÀ”) ü³¾ö°œÇ*` ö46ÂÛUU¸~|«aè‹úÚãèˆ'žXà·l˜õu‚å<–Kxt¢®ÞÞ¨«CNz÷æ[ CXÔ× ggLš"ìÞÍ·†Ž0ëë Ëy,–ðèJM ¼½Ñ؈ü|øúò­†¡5,ê늋 2Ëy,f}=`9%Ã=¨¬„$¢{w¾Õ0´ƒE}=ðð@x8d2ìÝË·†Ö0ëëËy,–ðèGY™<Õ).F×®|«ah‹úúáå…qã ‘`ß>¾¥0´ƒY_oXÎc™°„GoJJàç¡%%ðôä[ CSXÔׄ…¡© ð-…¡Ìú†€å<Kx Á­[ðóƒƒJKáæÆ·†F°¨oºwÇÈ‘hlÄÁƒ|Kah ³¾`9¥Á‘ŸÞ½Ñ©JKѹ3ßjâ¾èÙ?Œº:üú+ßRÁ¬o8XÎcQ°„Çpää _?¸¸ ´:ñ­†Ñ,ê޾}1djj’·FÇ0ë–óX,á1(YY „‡JJ ñ­†Ñ,ê”ðàƒ¨¬Äo¿ñ-…ÑÌú†fæL€å<Kx Í¥K<^^¸u öö|«a¨…E}C3hÄb”•áøq¾¥0ÚƒYßLŸ°œÇÜa øûo  ÂÎŽo5Œ¶aQß„†" %%8y’o) µ0ë–ó˜=,á1©©9Ý»£°B_Ìö©‡áÃÑ«nÝ™3|Ka´ ³¾qXÎcæ0ë ®+ÛŽ`)¥YÂr}£!“¡gO!- Æi{ôÝ»wׯ_òäIŸÚÚÚòòòµk×8ÐJmõ†Pˆ§ŸtÉyöíÛX^^¾cÇŽÄÄÄÄÄÄãÇO˜0A*•^§ÍB ãqô(Ô·¯V}óÍ7B¡ð­·ÞRl9|ø0÷aZ¢í¬oL$òö&€ÒÓ5<"99Y(Ž9R"‘(6VTTDFF~÷ÝwÆQi£0뙈è½÷4Ù·ªªÊÛÛÀáÇ­‹Ár}#ÃÕy’’4Ùwݺu¥¥¥?þ¸qU1Øc®ÑyôQxy!+ W®t¸ïÏ?ÿ €ù^C¤Ré¸qãD"QZZšbãéÓ§E"Qxx¸L&kÿpf}#ãà€©S`çÎöwlll¼xñ"€àà`è²ììì¶oßîéé9{öìÊÊJeee³gÏöòòÚ¶m›°£þ#ÌúÆG³iJKK¹ݺu3¶"«¡G[·nÍËË{饗d2Ùܹs ·mÛæããÓñÁ|?lØ÷î‘§'tõj;{ݹs‡ûD¾úê+•·ÊÊÊòóó)Ѳ‰àƒ>Ðð(f}“ðüóÐÇ·¿W`` €‰'*o,,,œ5kÖíÛ·©Ï²‘J¥#GŽðè£J¥R bÖ7 ¿üB…†¶¿×Î;€¥K—feeegg¯[·n„ yyy¦‘i¡dffºººèÝ»wyy¹†G1뛄úzrs#€®_oÇäää°°0gggWW×ÐÐеk×644˜F£…R__ÿÐC¹¸¸|ùå—B¡pÚ´iȬo*fÏ&€þó¾uX¶lÙBDË–-°víZMdÖ7IIЈ|ë°*¶oß`Á‚ܯ‰dìØ±©©©Ë:-›Šº:x{£®7o¢W/¾ÕX×®]:thŸ>}RSS;ÝŸÕ½¨¨hÈ!;wNOO÷ððhçpf}2cvïF|<^o) Ö¤eJØäæ‹ú&¤ºÞÞ¸wùùðõå[­Ã¢¾ quÅãC&Ã/¿ð-…Á¬obXÎcd2Ù¢E‹öï߯ù!Ìú¦eÚ4ˆDøýwÜï¬Æ0B¡pôèÑS§N0aÂIÍæ{dÖ7-xì1H¥Ø³‡o)ÖÆìÙ³ƒ‚‚RRRF~âĉö÷gÖ79,ç1vvvË—/ç^=ztܸqcÇŽýMýÊN¬ÂcrÊÊн;ܺ….]øVcUÈd²ààà«W¯*o5jÔòåË'Nœ¨²3‹ú&ÇˋƌASÓÞyó:DÇÐ ¡P¸råJ•þùç¤I“ ôÃ?(OdÄ¢>\=:øäÉ›A©·÷¡ÀÀËÞÞ$˜àº õõõ&¸2uuu¦¼â•+WÚ|kذa~ø!÷ ÀÖ93¹¹Ø²~~ç‡ ÙuêT0Ћ¨OIÉð’’|àà ‹oVÏ¥K—öïß?bÄõ‰L†ÔTaÆ $'cÊYHHpCCÅÕ«OK¼½,-mðôtª¨àv¯ò÷Ï;öæ¸q îîÆãää¤èæe2Mv¹k×®=ûì³­]Ý©S§ˆˆˆ˜˜˜=zÈ7«;©-ÓØHiiDD—.@>>$•R}=½øâ†‰tíÚÀæyó ooúë/Љ‘ÏÓO›7S]߉å1ƒ+ )áääUXX¨²'³¾á¨®&"ª«#//rp Š "¢1chñbº{—ˆöìÙ@$-X°Üêáà  ‰ˆ$JI¡Y³H$’ßAüÁãßdYœ={VÙôîîî±±±wîÜisgf}1g9:Ò?ÿ=ö‰Åtþ¼òû………\°‹‹ãÊÏ|ðmÙB“LÖ¼ky9­_O£FÉo€‚‚(6–nÞ4íŸdyÌä–ªWé•aÖ׃­[),Œ~ý•ˆè¥—H Ço.ü+!•J¹9ÕÂÃÃ¥Ri³õïÝ£ž=  C‡Ú8ÿ•+CÝ»Ëo¡PžÕÔû/³D._¾, 51=³¾–dfÒŠ´kÑûï@DD7nPAºƒÖ¬YÀËË«  €ˆš­ODqqФIj¯(•RJ Í™CÎÎò{ÀÝæÌ¡””ß6Ïœ9s"## Ô *0ëk€DBÇŽÑþýDDßOqSå\¿N[¶Èszõüý÷ßŽŽŽvïÞÍmiaýŠ rq!€.\è@FEmÞLãÇ“@ ¿  ØXºqCÏ¿Ï J¥999Z¬¯žº:úë/¢û+DˆÅDD·oÓüùtð †ç¨­­ ‚ÒÐiR±>½ö¤´CddPl,õéÓœEë×·N´íÀ¬ß Î@¥¥Ô¹3¹»Sc#55ÑСôÆÔبíÉ-Z@,×(%èªÖ¿qƒììÈÑ‘´Z4E*¥?þ ˆêÜY~têD³f±DHC˜õ•ÉèÉ'›-8h=ôegë|>E5ó/îÛã>ªÖ'¢§Ÿ&€bcu¹ÌÝ»ª‰PÏžC×®é¬Ü`Ý×€ 0|8þú \G‰D¾Îó©S8ýúévÖ¢¢"®~ÿᇆ††v°÷oÀ×_C‡>6nn˜;))ÈÍE\ŸU«Ð¿?~6 ºZýÖß÷O\¼H11”’BDôê«вeDD™™TZªÿéUª™*ï¶õ‰hÄ(1QÿkË!WWù—€“ÍšEûöQS“¾'·"lÉú÷îÑ¡CtäÑgŸ@Ï?ODtñ"%%öQ¥š©BÛÖß¶zðAƒeêõõ””DS¦üð󣨨ŽKI¶ X¿ºZÞ°ÊMý7z4ÑõëIÇŽã‚­«™*´mý¦&êÕ‹úï ,(?Ÿââ¨ÿææá¡C)!l{ârëµ>Å33Éɉz÷&™Œªªhð`z÷]£@Ú¬fªÐ¶õ‰hÕ*hÂc‰;wŽ¢¢ÈËK~8:Ò”)””D÷îëŠfŒ5Z¿±‘ÆŽ%ª©!™ŒüýiØ0“E¸ÈÈH´ªfª ÖúŠæ­–ý Œ"²·—ß=zPTýý·/j~XQ…gõj„„ '"ÑÐ /Ú\½Š´4tíj {÷îýöÛoE"ÑÖ­[;wî¬õñ˜7¾øÂàÚšqr¬YØ¿¹¹HHÀC¡¸_|ÐP<ø V­²•‰Rø¾÷ô#-Þxƒ¸¥¹ ìã㉈®\!W×0о™«V­jOµQŸtmÞÒ“Ë—)&†ºu“ ˆDòDHû&< ­__Oû÷ÓŸ½ý6ôúëDDgÎÐÞ½| ïh¿š©B{Ö'¢éÓ  + ¯²}hß>š5‹ä÷€§§°ëWTÐåËDD_}E=ý4Ñ_Qt4>ͯ4ꨚ©BÖÿã¨[7ÞFi••ÑúõÚ\8ââLúEd|ÌÞú\¡æôirp/ÖŸOƒÓ§Ÿò«KE5ó—_~Ñdÿ¬O÷›·6l0˜DÝà!Õ‘“µµ< 3flýŠ 1‚||H"¡†rw§°03®ª¨f.\¸PÃC:¶þöíP` i¼¦igä¤%÷“3?ë/_NƒÉRx€åy޹öÈUT3k5Ž…[_Ѽ¥qïhSPQ¡:rR,¦ØXÒ²£¼™`ÖÿýwZ¼˜22ˆˆÂà  -[ˆˆ.\ ª*~¥µº¾™íÓ±õé~W‹Ç×W¢1øçŠ¥Þ½U XÔÈIþ¬_SC;wRz:7-·˜ø±côßÿZDYMój¦ Yÿî]rw7zó–>(FN* ¸¹YÐÈI“[ÿömyt_¹²y`ë±côöÛæû·…VÕL4²>½þ:ôÒKº«4 ••ªzõ¢˜}†:˜­/‘èu.S?xììä}T.\ ‡¦/¿Ôë´ü±zõjÍ«™*hjýœ²·'GG**ÒQ¥‰É̤ØXêÛW52ˬU3ëÒòå:^!/BB(0ˆ¨¼œÜÜèÉ'Í¢p¡ÚV3UÐÔúD4s&ºÿçó‚bÀ×É\GNj`ý’ Ö®q±©‰–.¥jl$‰„¼½ÉÅ…¸©Q,´„ÕL´°þŸ@]ºXÖ¤œº:JJj‘ùûSL eeñ­Œ¨cëRP´m[Ç';tˆ,;‡„ Ÿž)#Ã"[5D‡j¦ ZXŸˆFŽ$€¾ýV·k™yyG< :`@Í”€¦¡]ëß¼Ir­\)¦5••´m›üÉuÚ4諯ˆˆŽ£S§ô}B0?t«fª õþY>厅g‰DDçÎlä¤Þ›ê­éRó”wvvT_ßâÝ¢"º~ˆ(:šŠ‰!":tˆÖ¬¡Ü\=5™-:W3UÐÎú õëG8 ÏE͈Ö|})*J»_L ]¹¢ 5Ö¿r…zôhþz oç 5?þHB!=ó ÑÉ“4y²|">«FŸj¦ ÚYŸˆÖ¬!€ÂÃõ¹¨9RP@qq4`€j"¤ÉÌ+VPß¾íLöØ!mYÿôiycŠâgêTº|™¤ý‹ˆ('GދÖЧš©‚ÖÖ¯ª’"êÒNK‡9Ùµ«#'ׯ—â×õ¡•õSSÉã…ïZº”jjÈÙ™üüä¥Ë/Ôh…žÕL´¶>-YB½ð‚þW7_ZèÒ…""¨ÍǪädù>ÇëÖnÐÒú¿ÿNnnª¾ç¦ö½p23­áIK{ô¯fª ‹õoÞ${{‰,¦yKŠŠ(!A^$T0PRҼυ ÍCñWÉú))ÍÓX·þéÖMϧ ËEÿj¦ ºXŸˆþ÷›§Ê²¸*K-q#'ïÜiáϧžÒ6¹oýƒÉÉI­ïãö33 ÿç™7©fª £õÓÒ,¸yKå‰bÀ7rRűӧkUL¿?#C@~ø+Wâ™g‚6—¼+.Fx8nÜÐ,¼¥ ˜7ó£>êxÞLc3lþõ/”—ã‡xVbbD"<ù$’’O?…XŒŠ lØ•ÅqwïÆ›ojqڶrrè×_)>ž^~™Æk¥Ö»·,ꤨfŽ?^Ïj¦ :F}"Ú±ƒêßß6ºš¹x‘† i;7ÑøU›NËååtú4mÜHß~kVýŒ„¢š©ÉÂLZ¡»õ%yûú¾}†•dI46Ê{ÔýhÖØžzôQC‹²jjhâÄJ…Bù(¿v±¢Ù× G]]ÝsÏ=×ØØ¸pá§žzŠo9-™?8v éé|K19••˜0‡©ÝÁÉ ýû#, ))¸s§ý“ÙXœU°dÉ’«W¯ŠÅâ„„¾µ´ÂÕ `õjÄÇÛÖóni)&NÄùópw‡¿?üýáë‹^½àë ??ôì __­¦—dÖWeÇŽëׯçæÍtn³ÒÅ;ÑÑøüsüô>ùþþ|«1UUغ½zÁÅÅ çc O ŠŠŠ/^ 3©fªÃß3f © _Í·òÀ8ÐP¾³¾22™ìÅ_¼sçÎøñã—.]Ê·œváä}û-jjø–b©0ë7Ÿ’’Òµk×Í›7 …æý?óðà CE6oæ[Š¥bÞ° IOO_¶l€ÄÄD___¾åh·èâçŸC&ã[ŠE¬(U3#""Ì®š©Ž§žB@®]Ãþý|K±H˜õ¥jf||<ßZ4F(Äk¯€i6'˜õ-¡š©Žyóàá'–Æ·ËÃÖ­ŸŸŸÿòË/ÃÌ«™êpuÅÂ…€‘×Þ²RlÚú2™lΜ9PÍTGt4”„ü|¾¥X–dýãÇ ‚+V¨l_´h‘@ ¸zõª¶'\»ví‰',£š©??Ìœ‰¦&|õßR, t¶3 b±Øßß_¢4§¶¶ÖÍÍm4·º6µofûèÕs³5çÎ@f»ú†yba¡îå—_.((øõ×_[~ú駪ªªˆˆ­Îc‘ÕLu ŠÑ£QY‰M›ø–bIX˜õ_xá…N:%&&*¶$&&véÒeæÌ™ZÇ"«™íÀ5o­] ©”o)ƒ…YßÓÓsöìÙÉÉÉÅÅÅ._¾|æÌ™9sæ899i~E5sÛ¶mVÍTÇ´ixàää°æ-ͱ0눌Œ”H$ßÿ=€ 6Ð*ÛQ®f†„„I¤© °æ-màûaC† Ò¯_¿ÚÚZOOϰ°0Í”J¥cÇŽ…Fšk…s9jkÉË‹JM5äi­Ë‹ú"##oܸ±hÑ¢ŠŠ ­B¾5T3ÕáìŒ àóÏù–b!ð}ïéBuuµ««+OOÏz•ÙÏÕ“ššêàà>ª™*%êQA‰DdooÅ󼋌|...Ï?ÿ<Ípkjjž{¦&k¨fªÃϳfA"aÍ[š`‘Ö ‰p¬šðæ›o^¿~Ýzª™êX²6l`£·:Ä"­_UUµiÓ¦1cÆ 8Py»T*­®®n½¿V3ÕбcQY‰ÿû?¾¥˜;fýóçÏÿøãÓ§O¿{÷.—1+“““³jÕ*•ŠjæÇl=ÕÌvàš·XóVûX˜õ·lÙ2wîÜŒŒŒÏ?ÿ|üøñ*ïfdd$$$ܺuK±E¹oæ.°z¦N…XŒœìÝË·³ÆÂ¬¿zõj"*((ˆâZpZ’••U[[ûÙgŸ)¶Xs5S^}`Í[`Unàú-ýõ×ùùùÒÒÒÞ}÷]XÐHsCñÒKðòÂÉ“HMå[ŠùbUÖÿçŸ444¼÷Þ{6QÍT‡³3¸–>3œ8Ñl°*ëgffr/¶mÛ6þ|›¨fªãÕW!açNäåñ-ÅL±ëß¾}»¬¬Œ{-‘H’’’6mÚdåÕLuøúbölH$X·Žo)fŠõL7Ûz€bSSÓ¨Q£z÷î-‹ƒ‚‚ƒ‚‚ÄbqWmæãµ`Þ|[¶`ü÷ÜÝùVcvXOÔÏÈÈh½Q*•Þ¸qãàÁƒkÖ¬‰ŒŒüæ›oîÞ½kzmü0x0ÆCU¾ÿžo)æˆõX¿ýaé“'ONOOߺuk@@€É$ñbrB‰„o)f‡õXŸ+ï´&<<<--íÀƒ6±$þ™2AA¸y{öð-Åì°ë+Ê; ‚ƒƒ÷îÝ{äÈ‘aÆñ"‰69¡:¬ÄúµµµùJs0õéÓgóæÍ.\˜:u*ªÌ‚^@×®8u gÎð-ż°ëgeeÉd2ݺuKHHÈÈȘ;w®­ô\hggp]»Yào‰•˜###ÃÕÕ5666;;;::š›[Š!ç•W a×.›Zé¾C¬ÄúÙÙÙï¿ÿ>7p‘Ñ‚=ðïC*e£·”±뇆†vëÖofÌÒ¥˜ÛiÖè+±>£ Âc¡º7ò-Å\`Ö·¸æ­/¾`Í[Ìú6ÃO (¹¹Ø½›o)f³¾Í È''\½šo)f³¾-Á5o=‹S§ø–Â?Ìú¶D§NˆŒXóÀ¬os¼öœœðË/ÈÎæ[ Ï0ëÛÞÞxæH¥øòK¾¥ð ³¾íÁ5omܨڼUY ¥åj¬f}Û#8áᨮÆwß5o”H0{¶M­@ʬo“pÍ[ëÖ57o½û.FçÎ<Š21Ìú6ÉÿüDn.ví€7e³>ÃÊ «WãÄ ÌŸ/ßîâ£(ìo”—ãæMTTàÞ=ù–^€Γ/¶ÎÁ¢>ÃÚJ1w.ºt£#Ð¥ å³ß¹Ó¼³>ÃÚèÖ GŽ`Þ<HPQÜܦç`ÖgX!"6nD|<ìÕO¹Çr}†Õòúë8~>>m¿Ë¬Ï0 ;wîüÙgŸ3fŒ‰4ùûãèQL™¢ºYŸa@¼½½/^|æÌ™I“&5êÈ‘#Š·:4räÈ)S¦œ={6**ªK—.¦“忆}ûåÙŠl)á߬ŸÒÒÒ~ýúÕÖÖr¿öêÕ+//û—Ûâææ–““cRë+ؾó磾"yÀ,ê›.ð+~埧´Þ‰©C¾2ÿþ7~ÿþþ6•í€E}ƒ`oo/mµH­ŸŸ_AAâW•À¯ Ÿ!_AY–.ŦM|j0-Ö³ª ÞÞÞÑÑÑŸ|òIë×,Y³ïxyÙÚ ,ê˜ÜÜÜ#FØÛÛ§¦¦úùù)¿UVVÖ·oßêêjåžžž999îlÁ“Ãr}CRUU5yòäÚÚÚ¨ø€——×kÜl÷JDGG3ßó‹úC"‘<ñÄGÝ»wïäÉ“ÛÜG%ð³Ï#,êŒÅ‹§¤¤$$$¨ó=//¯Hn:À+¯¼Â|ÏÄ0«V­Ýáž%%%;wàææVVVfmŒ6aQßìÚµëwÞ™:uêÚµk;ÜYQãç³–Ï`¹¾þäåå‰Åb''§ÄÄÄÎJ­BNNNãÆkó²²²ÐÐЋ/²l‡G˜õõåܹsm®Ð¨Ò¤¥BFF†X,6¦.F0ë3l–ë3lf}†òÿ(нuéÛIEND®B`‚opengv/doc/addons/images/reprojectionError.pdf0000664016516101651610000003154313344612246020507 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœ­K’$=nç÷uŠXkâûq­Gs„2“zQµ˜ÑB×~€î™¹S[[[$ñ&Èïÿ½Ò;¿ÿ‹¿¿ÿþúן¯ÿü¯_e½k¯ÿþ¥Ÿ_ÿþo¿J[õ=Ê«æÝ^å±ßc9ôç×ÿvÿÿ?ú®«¬Ó®¤þι¾jí½†µýìyýžK}Ûß?¿þã_þ÷cüÃfTÚLï¢ ¯w±aÖïQë+ÆV´WIïžÚ+÷Þ­Òj–woó•gKï´­Õ÷~{æwÝ0u½‡ÏùŸ4RÌ<ÛbÓ|×Íò› ”mäŒ æëë'~ÛlªIÄÛøkl»’_8ƒ÷·³Ekpa¶Ž¹¾{U#¦T¯­¬¾û,Åhrm—q¡‘ÆÚÔ÷bèºçbuŽwšë{/v-™’°Õ›WËpN]{Û­W}ÏÍŒ¾c½Ú;W3™X víŸ4Ô?>¸Ê¤ñ]ËkšØ Кõ]7æÏYÍ0ÈßÕk—7*èÆ¼óúÀØ÷íÿ/ƒ;Ò°j·m^ÀYZ­¿›úÛzXgêÕí;™y²?kØWª-¡Öi°‰ÓXêQMiôך6ƦEïiß\Æbšf¾lËZU‡n“°!—ë˜Öǰ–›ö«t˜6À¸`zØXãÑ`‰g€sÀãÝù}¾· ³:lØÌlÌɈ-ÚbÝÆˆ¶EÀg¦{M ˜ÔêÅÄÒtK‚a|ƒí›B?j@Ê)Œ-ˆ ¶f× ÞïͲ›}9z8¦™ &IsßFÜ/˜üÞ]ä6:8ƘÆØ´ýÒÊ ûazygà‰h­ÑM/øJlñ3òY .¾cS¶Ç†5ïL#¸öjÑì롈z&¾i雯êaÛ—À‰YX×aß0-°E_ëj²¼º‹€z'¹ºñ¦æ´Û7š}³ ¶oØï Åæ›nú#£zÚ{²Œ‘Ð|«X‡ý€ó Uu0„Ë {š×ˆ[¬NŸo#†!6À|cˆ6ŸÛñ½š¤“]î?a½\н)ã#à0Åo:U0°ÉÙ0æjØ6\`þad&%Ûx6ßj¤vù2>€Ô e:¿d·io’mó2#3—deô‰‰Aù6Œö¡aLiû \ÑúîTø„Í(Áù¶ÓnÀcÀùÆ.ûé0ÔGãHFtÐ&êö!:˜¬©)ÏÌL\­A=¢¶§¯ÈLSò%›^Yd³9š?UÐÒÐ(c<4ÊŠO“žD56ÌìJÅqà‹U ©**cªöÊ'9Mz n¾h Rž°©ïŽè:mzlƒ­º˜M5¸9ƒ ÓöÇ,àƒNÓùѶ¶:ÝÒfV¶±£ë›fäÕãLi³jÛYñŽ1agJ¶±°©­Ñµâ4ñC¬´0ÞÓ$ŒL‹®q†õ­ƒ‹Ô4©e«K1‚ç—`ók‡œÁ¶‰ï~z¦Û¤Z– š¦opbl¹øOŒ;`ÊfÃ~Âܽ̎˜ñ|ŽìôêÌý‰±íË…ù¶¦#…•ùÂÔ6iWm’‹&v36É(^d>´©ëÅ]Œyý^á7À&@„†f¦$ó+¶È­±7d¶K]°9ZÞCN9BZ§ùÖÛAs³M|‹Pÿâdç\à Km¢f¤š¶\í¬æ=’¯Êø³,ïÑE3ÙÊc×hâIwÛþ=>öæ`®ýfì³?a®^èöø90=˜³£Ãö|oè0ÓµúsG‡¯Ç†Ž!>:;†2+ã±£+“ïßûC³£Cð\Š«š"±]· ^}G§´gsc‡³k¿&=¬=ÆçBaËžÌPn(ˆæ[¹áïkKÍî[ ÔÃò°ðØòø„#ž„´YŽ¡»0÷†$9A?aî^˜{Žì”¯G §ÚKüÀà×™C)Ú/˜K'ë·l[MáÁ@Û¿ŒYŒ†ç|alãeM9ÊG±2¸à~â,—Uä.âO`ò & ·¨Ên6 áR˜:í~17õظ¬Ýö²š¸7ŸŒ„C´0­0n•å¦vŒMï¿Æ¨sèÖð§ë­éaœÅ~Ü-îÄ „OÍ÷tf_†ØÅ… áŸµ¬of\Öe1ÙÚ‚››‡eá’fa“´Pò"&¶X¡pO>+b—.Œ¼xͲº®°0Gx. ÐÁTöC"K¨WåÖkH6ÄØ#ã°ðQÃwÓ´¹ÅG}ZP¹©‡|ïn¬¡µu%W%°:%::ŽÈßZ´‚v¶mN£¥­ø¢v'àí&„›!Ú"p`þ—YÖ~´7‘ϰ©¨þÆB{i†­È¹_DÎK«ÚÚÎÜ´Yx] 65}*­’az6ÔKnÚJ.ŸÆ(M_4†)µÙ)íéBï—³’L’Pæ^—m â¸0ð|£eät)–PŽÝ9†Ÿ²ûøÑ®‘âúpî %þòÕ¢»g·pÚµ1îK–åSnžÞáOT¨Cb»ŒÊ®‡CËEY¦þW‘¾ï˜\¢J>@àŽ›ñ6ök‹*H¸æMzæÀ}7Åëêá˜Ð:¾é!0xÙ[eQâA_oŒtÎ~zǸkT³HñT–Æc-ÒbO©q…Ú¡‡F©r®´Sl{’^[4΂ùK²HÑh‘Ó­é”gñÐtºnœ*I¥³ö=L‡À–ùsaî>£‹âטÈÞúø*qá|Ìk('tM{IJïe eŸî…w…e7aº;9Òu…mÛVpuÑþsw~cK6‚t;ÓÁlqÛáÔ}›ê¾ÕK†Ù˜y²Ïn£îp×FTWóà© Vúþ ý¹I u·…„ \x$S<²—´þÃ= '™4ñ‡\›ßÆDŸà¿]0±Lôæ¶É=…®¸ìö¹lû6%[ë'&#)èú £-cdé (‚5 #¹D±qüƒíjo³÷Rõ÷i"ƒï¤‹äEš½»û´q¨š4'jrctÃ+AžwS~Í.´E:Rµ8ÕƒYFî(æ)~jî]•¾¥£d 6ô%psÊä$vÜ„vUS’C¶Í™n ¤w¾¼"RCôÈUËÂ6ãômœeìlè˜p¸jÇÎÒÃs?ô‡v9á`l}ÂäLƒPÓei5f‹a âß4 v°ÁI¦Íñ1ŒIñÌ4K(G¾gA[ó¡1«ËyQ=DíÆ¤Cüm”Àê‘OÛ¢]u‹²ÄW¢Õ R~M=|ƒwò0ê#ÆA]å_dà”HÛURØwu~Ý6ÁxÚñAr Ìhb¢ôöÚÏîûg Êã·sm›OlÀjíÓ•ðœÝndçìÍ:k¹†P²p’Ú»R<(YZ›Ò‹êÑ•SÀGèÓõË 5æ=²¾!ù7ºGôÚÄÓA8ƺõš¤c=ôšä£?¬Ò†g‡Íìy"$Ò;Æ $Ö˜…ëòió'nøéñËÚ!S#Ù>ˆgf#ÿˆ‰üÈŸ`ŒîIœÑ|Ü®æ®CZÃcrVBÏvW¿R’–‡zþTà¾ÃƒÝÝ•'ÙV”e³laÀL‚«rÃb7Øg¹Ò¶Œ"~¬ô‰ý3Ë›pZmI'f¡]RÔM-’Ë™šáò€ÈGПÈpIn9ç\ªäšhã†mCŽŒ9æ¤F7ùš;LÖž‡–>’o‹®ÏÊÞËïORšf`§kú’}“MQ÷ã[ Í.¿¾¹•?¤&w_ËÄ'^ëÉ„°/i-Zý½1ÆÈÛàBb½GLbpÆÆ¢¡×oë±0¦ú2l`p¸ÅI6Ö`y=·ö5LRô³¾1#± t¢Ùã ‚ÿÙè04èJ^ apõ.b{½d…®̓‚=²,Ζ/Bk÷üÀøŒ+yrÙ0âaƒ³´hMÒÃô(:lè’Z˜RaFU9p«B?_Úgéiüþ&sº›U<.ƒ—˜­Pü !ÃW·<nê'f{¬7d“ÀTå]O\«•ÀÝxI+ >:œgÄ(ÚoûÝ1xún-_I—™öh¼rÿnîÃÞr0P²‘õ½[7•’ì ;àŸÙœŸÜòÞðŒãÂ×Áî§)/ÏÏÄ-Eüuå cƒ5IhÓ˜œmZËI°uÒƒ¥-¾Žý1´Nd¢v· †ù·tDÝàd—94eN6}<¯éi†d;€Ãa|mVÇɪútR–ØT• µð¡ r›–‚Lñ`Q¸ÉqUaHT±ÜUBviËNû1QçLrLÙeì™Áòu9#€58I‡>ÌÎçÆu¸í¸–¢“óØH =o8—Ж7ÆÝ4BSò÷Ql]ü¨eemcÒä UD 9sV§u#„ò®G*gÝEá*¾¢ ÁK;¢§ìÉe…DYé3ý•T§cšNUL­ªÔDªœd ;ur?ÐÀ¡›‡+~T-ÆuÝ™ãê|à¸NþhÑ"2óÄm’Añí*¾ÓÂûÒÊ·–àÀóŒ„÷©®œÃ]1o—’”Ãùœ¬ÅÈ%lG»æPuz”jðq“— —Öж¦Í=öU÷ìî¥3¶¶åFñMõ-ïöì©8`K0\™:@…ív‰Z+\X)TŒ;ÁÛw¦s ðÕJj»|»>MËcãƒY¦Û<|ûã'ಊ|^£¯íYÐzp»… Òœ®&ØŒcÈcª§ÎÌ¿šnBæ¯uUÉðö*¸êX÷ oÕ ñçBTSIþ×éSIµþÄp²’>0̈́ʉ£1C54îJ%I¿ø{håÈÑþU9¨6~¬1ÚXýgLP9a´?û¤™êб»a¦¿£Þ\AÍgÔè8ÅPuðb 1š9•³¡ÌžÊ;ðè.˜U¾ç£‡8‚qd*gMÉ{$5TN£èa‘jðT ƒ – Þ಼‡òÌ F2°ë|Ó`%/¥XTz BÍ!÷·Ù†p:\9ÒÓMÙ2‚©âì4Â×9˜:jdôQS>OLSܹÍè9÷Õ0Ý©E>غP=‘‹¯]ð CnÔÙÈ@…㛨5Ù1¯f¨:v›Tó¬ý;¿ÓUåJ¡ê{TEÐ’¥â‘!M‘j¢)§ØÏÎߥòmøÂU·¹_B*]àº-ç¿rÌ7T¨½G'€«}èüT0üÊ1V}àéµ “›Ä2ˆ;¿#n‘Š.߹͈qÄG¶ý'a´'FIÌýs÷ 9|Œü)ñøø•Ìw§îÏóoŒr\Zƒ2—û“ Unž«ƒ/pc >¥¸ÔàªQI‡£U+sÊ›‡èuÁõE³åÞ`'Š|2ƒd?2¹ƒÅpÔïLÁì·Å‚0žÁ=jX ƒ¯d˜&'Ú`ò‚9m¯”Œ!zÕÓ£øÙžYú^|QYIšt}`8ÊX¾7*Šù s÷2GÁ“ ×ÈÉè§?zå>#ÍqaÔ`¦­rÆ ‘—­b¿C–7– “äψ “B<’G05¥MŽ@#-ô‡èú€MbkSÐnÔÿ™t'o¥ 2ÇWU¬‘©-@Wñm5µ“bë  Œl1Ó¾ÎØMõ(þý%M‡j˜2Š®¨2ðÂP¥­qvSËl¹Å„r!ÿ›_‹ƒÝé,Hˆ$’BRg •@Ö×§F¥K{Qùæ>råü@Œ.cTÎ/Èù ·&ꉃLóŒ÷C éôŒ ÒˆÅO<œT_¨n‡­‡…f:;59¤Æ›¸X/€­³wPÐ…"è¤ñ¢MÏ!;7?Ñ%—£9‘)ÔÙ…Eƒ¬sçí™qÜà|„Ìùût(¤W^¶!)Ëì¯Ã€0,j«Àxçä‹pLWVVOÅ4A*µ… IgAú¦¢4›u>KÍŠ“=ÙxfO„“;W?™4‰?=ü4“¸º2Íä'¿å&É@÷ü u’'Ïb×Öa~§3±¿Ûs¬k?=%uµ˜3¾™ºÃÙ3+:À“uqmØpL¸í¯}g¬ê ¸@»A@KN1æ fDD VÙ¶ECþÓò#EØÖL 3°ÓØd%Ù D¡:c;œÓRªz8FéM¾ÑĆÈð+­ž9ý‹Y / &…M-1ç¼+?äxë°ï)Ça½[Àؘ%JlOè·-²bšÃ¨¨Ÿ,Y(ÚàÜ»—<‰‰j»¦YInVY…!6Ýn4’’…´7{I•;•ca"Ò±þd7!Ã3GWÞÁ¡wþ|ÓD`vrÍíÉ~tŽÒ¼0•cLÊí™·TÓJ>í*GOŠeÂ%ZB»HsléuoŽ*’}[Ã{øW9ì—oeÊÌüÒÌáMë®î •Eƒ‡uÇ”)P¥Js‰© 3ð„‘3ï&1n8˜?7æô®÷’Àùü¨Î5ú=­-g÷ž6LPçsa;uwbé;©nþ"ÍÆô—âyqïM^‹åtâÿsƒ†*'[Ú7À”šw¥Êø`nsËù_þ†‘ÅÊ´ Ó|~S¡—Áª‡†‰SÔäg®^¤HÖÖ­ÀQ\/ïwo…ߘTi­­”ßô‚ Ã(ôÃ!MJÔIH®Tœ’BfäNÂnˆá#DeJòŽ`¶”u¬w‹n#³Ãœ¯¥«®#ÜDV¢iŠ®{ Óå·×¢šiNsÈ$ÀS»è²ØˆÛá Vv¾‘Œà›1LF@ .ñuäôè:sÏ4"{tž'±Ü_u÷7ƒ ­¢+{MÊ» ŸzýEÑ™J×IwÚd¹•éɪ@ÑÄ^PAþb’É1#ĉ()Õ)«6TÓIF‹T3ÇÄ^æ£DžFw?Þ&Æ6G÷_n“ãûù09›+ ]FËÍÚVahÇ3uíG©AØwSG iβ¤Î³œ>…rF“’§#¸kHŠ~’TxgÊ£ýâðß0E &)1ÌReoãñáöšà&'P-*5¢8㊭Å‹¢u¨^ãVvo àÚ´G[O¸L÷c““;!ÜËH êÑzËk—C]lÕÉaõÓÇoˆ»Ï¥)®q¿êÆeÛ«Xot]ñ8›)lÆ“¦’1K‚ ¬”¹]Q÷T¡(‹¢§¤š‰Cá(Š/žú]š•T%£ ©J¬Í…j®8q€³¦[Ï|$SŽà úM‹”UÚ}bäQ>öÀâ½ìÊË1R=R¥U©,ƒ+yàtvzû¢"«.æKn¢ÝWŒmâŠRznºd„ªJ"A¿4Ä–W{“ªŸ9”ä£9ÔD‘Jì’’€kÏÂ,Rôè-¨¶!­ûn:+‡ÜÆ:áSk{8Ú|-UƆÚomÇ P‘ V­­Gp}a®Pº±Áhë¦Ê±½ƒëF˜_oLËe_‘uCjÛ#²nÜ>Ü㊬ †ôWdÝr(÷\7ì;6,‚kƒu¦r‚kƒ³¬ú\7V‰ÉŠàºá Õrר¬¯Gp}0wÜ¥QO˜|a®Pº‘jÝù'ÌÝ+)+õ90Oùô^·m¿0—%·º/ùÄt'{×ZfžWp-2Œv×F¨âÒp‚kÃt4aÄ×n×_³UàZ[ ¡#¸nhÈÁµ8cGpÝð«F½¢kqÓz˜v©‹Óþ…'‰®¯»µu‡1¢LpéžÓ3êRfT$H=q†ØtñÒô¥ÄAy\Á­ÛkAÉ&âÉɘà©ú%D»ªÞ‡²owà“2Ž€‹ÓO˜, E+E~oE Rõ>«»ƒT”Å÷ ÛŒ9Ç¢ÜQÀTš ëÃñYRÞQÇØd.—òöÂ57ODá~Çm)ŽèTáPs\©&±OXJ®#„#§Í–…ëÊæ›>ªç¨\ÇO°½&ˆ"êÓ5à ÷³"†ÒH¦Qï!«nÜm–˜¶>TëÖ‡*c;"ù¡ié£kÙ*´j½aNê¹LÖYž €`Št¸:ÂêPH°VâÅ9a%Äu:0ñÚðº›j Ÿ˜¡cþ¡ ±>õ!Û­ µªØ±µ˜7ä‘ÅT%Æa¶ßߨï›3ÓÄN˜+rk_ÖôïhŸtQ°©O¥Š.Ý0£ºßz·Ð¡%á—»ûY×Ó¹é†á?á‰uÈ~™hÄDÒ4mjw2Ú8;¦d]ÊTŽÈVÊ5§¡•fEV¬àânÑä;“ã.š#ŠÏzpCª¸™ž\•AF“?¦’ØÉ1¤Â2Õˆ½Èn¯çùBº£7²®¸¢Û«à`]kK;Hݶ•HĬ…»¥²”¶ÙF´AîøüN=sTMQå¯1k!l‰DÏšŒP‘p)LL 1GÎxp |y“`¶*²ä2›Š((ÔRœi °_c”è(n-Üiî°59¾W)ùœúpøwÁÒôŠ·ïUÅu…ëó”ïcMÍÃ48Å}-…¦¿Ý¸)äFf¢¡¤Yù5&W6?>ºÓ #Úe™7ì´SœMUC‚qȶ.’=á7x/L‘r¶¥øµ{øŽØû‡Y XKӌܚ-Sµ\=ÈâzJéÙ*Ëq£Z˜îœÀ`§²‰¼‘lùi]–7zøì÷WÆ“«¤Ë­%OÝ–Àå*¾1æ ñm” ÛYÝ’Ý73|`ö~é‚ÎÕ>J1&£IŽ’Á¶ÆÖŽïNÓtúáLš2µmôSÆ JŽK'¦&÷ö9„£1ÀÀM}`z qÞ-¦üê¢Ðx+à. ´»Ó†ãS¾ZÕ#gŦ…ãç=Ü™"éìä÷7âéÒÏàQ ö†ZšÔêÁ¬³·¼=€oÅl iª÷4l© î2õÜ·)5;? Õòß°œ ï!Lá0_Ok´Âýµù3f°œ?Þ«N'sÕM¥‚dÅÔÚ9B…º?aîN³;e¿cîŸ^_1¶•}`h”ÌÊü°lÑ©û‘˜ÂIi„ÒÕ7cüH”¾ƒPŠLu+(>0=†®ø!êÒp+G-ÛGhZÆŒý­šV©ž> Rˆµ†z²Ir׸RŃ õí5‹Sðéë"¦¬MeÛ’Å™sw2x-zE9L'²‡¤8sßõ‚i?r:Z¸!8.ü}Ïëš«¿ ã3²S÷XœÌl„[i 7¿u¥ J•V¢–Àa¥S VEeAÛ{`M9„Ü ÕÿÜ|‘; ó ›ôžöû_ÞwñÔ]ÆÓK!ŒL˜^œuÀ\½`Èñ1²c Aš.ê§ v +Q0–‹ëí;´1$…¤§øJá3°ßeOË ‹>~.Îtm»ìàŒ9è¡*<¤-k*T0X…Y…<0•ÿÕïîóp¥˜ŠrbgÛåó#•X½xP°‡;µèf’0äÜ$ÓwP+:âÝFø-yÒÑgõ¤õ…9ûQ–JI~Ä\½’gó#;FæÖ}•âg‰·Æ37F*õÏ­’¾cBmÉH7ãÝqËÓ߆[—â‡FÁjûÄ$w¬Û´ UtŒÁÃÕ[“ ÞxÄG£ì~ròDvµõåšÄ‚®!xW©Ì…½¶h‘c—›œÜ?V÷šËŸÄn’2nî¤ÀÇ[í‹»5Tz!¤oþÂc{nÌÙBrµŸ1W/?Žì˜‡½¤\ýÝž sù­9+<1%?½œAˬ! ý%*¸·“¤¡Î…›¬×Þb#†%™FXª>C|Ù̹]©WL§ën<Æ”ŽŠ•ÆlæŸÍÐÉ\zm“о[G7n·§ÿ—âUžÒ¸Tnè®å)áÉ&“×åþBÏ~TLú‚lI×…PâIöozxù,CHa ù”Êrì…Å=9zÏîq¨ª‡\¹gzXGUÉÀ5ÖÏ%…{8_\(Àô`{ú£E×ÝÁ]°4‚§Ã_ÚÆÒÉ1 ÙC=´ãš’ºôÀY*á4²Ò±=:ºÓÜ(•{†-öoÌæ «ž#\LÑ¥Qršô‡}îÚ¶fJô3™<‘i6ߊ.ƒ«Ï¹÷Ïm9Ÿ`L¨ëš½&<"B­þTÐqãe ÅDòþÈvSý/¢9yED¿¶/2ëÉ ywxÖÜ­‘ò ïÛ'’äãý5]W¶ð9ü¼AUŽ~(çY«Ü=Xåò d¥ T³TxÙºj.r¾ì$ÿ,ë–%Rr^àù%¤Çâ` °ô¶ÒB„»,mG4°UÜàÂq®ëÞƒ Â^D σ@è4§ÊD³ˆÑÃ+’T¨Pá’`=.ðá‡éšÒz´èåòìôT×bÒ0t÷ù¤Væë°§ôNÒó_Ú]¹]ñhÓ³;7õ8¿jò¶î[tÈÿ¹AŠàÆJn&–âÁ¿ ·dõ€Lèž©‹ÛzPf.J?×$‰§Gá${ÆTèã*yúóWǵ[þÐÛ˜¡ñšc„i¡ðLÊhÜ“ðGkº2õ®±ôF̸¢Uõ¨+âÙ£Ÿ†(˨CvãBrv“ëG¦b6)•|̼:y)뿃ÛJRÅ_ü»'ÀùÖË=¬¢’ÇwvHVŒ+¥$åD„ xöÑ‹V†›~¹Òþ`l*Ôe”D‹¾³„­øyVÑ#Íá±ýLb;ý×ÃwÖ³ûiyyXjìG ŸÍÉ ÀEžy:)îÕH÷ë%$ØnÅž—E³y„°ß;Ó OïùƒP#7Lqká—f…IÎÝíÜ»"5»¦?AX»“/ŒÎ ›¯µÎE\µÃ¬y>T»Sge >«øýëÆèÙ?ï](€Ö[ƒ>¼ØÃ‹˜€_/‹õñáÏèYÀ\ƒycuKÊ'â0O'“,ÚÅÆrÆ,Æxݤ'··__·B„1“ný}`²çŸk »Íû,)<Âl¯'—¿)Rï¦Ï€‡Ê8pï¡{D‘ÇÛf¥òo"aµŽÿ䯴s_$‡¿T²¿±ØSìþÃaÒãÞåÑb”8â‹zðéýgÚg ½xŒ¦ØÂ»¹Ñ"t–Ù† 2´pÁ.B-TÚ¾I œ×Mê ö͈y¹ƒA#(ñ›óõ ÅN9žæôË {ùYqÌRçðùZ†¢5·O±PzaÔ áÂwQJéÔÏQÿfWè¡õ@^²x…˜±_w ßÏ{„5?>àÜpÍÀ™åž ³Ós ÎpgÁ ‚cD ž¾È<‘ù‹Tø {\ºß—ÒDRHD>õê…8ªw댟1W'\—ã™À<”qôz(ãsToÌï;æù?üý¡µ'º8j˜3òw…¨öÑI'Õß’2îzØPÏ9dg€æo鉈[ùúƒ·ê€ú£Aöh|è1;‡äe/å$YgIéÐYP)zE‚jÉEõásøªÄ륕Ññ®J ëì/R”ÇGÒáþôÏv/L¯^´pý= ¢g5æå@×룛õH·öÖƒ$óÑ`f»‡¿vY•>=EyzèiÅ'ô¸‡ŸQ¾³â 7þâÅÚQpÿœÚñC \®êGó*a– ÎÙ‹Çy:,u6“G„ެÓßÌH :(?nv:Ãs+EU‚1¢Þ·90‚yÍ ÌÅêzž(÷«?0ÁØ=û%¹ï˜›Õ;µgOWéF„(v*ÄÆúÀ| ‡žˆj¾¢¤Z±¿Æ3KzÁ¥‡rÑ}C½É£ó]£~Å#1îX(9¢Wz”³›rÛõ¬Œpªº&^íñJ¨¡KÀzÒ¥FN¶ú;S-άâ©áfÂ_ïñ7šîs6xê†Å;ÜŸh1ëån½µÜiù,cé¿GÄ7×tîôSeyïg'•Œ'YÎnsÀ©¹º;ÝŸëLžùô·^Ž™îÐôzxvVϬw¿ªì/f³~ÖuþžüÝï»E.”N9­Ó±â׃<òì«?zí8—±¿lÿï«È—ËÊßêò‚ æ_\»6ˆ¯ü*¿þ;SY…ÓªÍËËl¸ð~ýÒëÚendstream endobj 6 0 obj 10564 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-13T10:21:12+10:00 2013-08-13T10:21:12+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/reprojectionError.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000010869 00000 n 0000012553 00000 n 0000010810 00000 n 0000010670 00000 n 0000000015 00000 n 0000010649 00000 n 0000010933 00000 n 0000010974 00000 n 0000011003 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<19B4A588A968F013F544CDB64EB7D530><19B4A588A968F013F544CDB64EB7D530>] >> startxref 12801 %%EOF opengv/doc/addons/images/relative_central.eps0000664016516101651610000010143613344612246020332 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/relative_central.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 11:38:01 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 638 717 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -9.888385 -31.647700 translate %%EndProlog 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.678431 0.678431 0.678431 srgb n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse f n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 22.640200 30.396000 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse f n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 15.902900 28.523300 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 19.603100 18.049700 0.212500 0.212500 0 360 ellipse f n 19.603100 18.049700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 19.603100 18.049700 0.212500 0.212500 0 360 ellipse cp s gsave 16.205400 29.774000 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 23.205600 31.135200 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 17.017900 29.969000 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 24.030600 31.460200 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 1.000000 srgb n 16.144970 36.373257 27.246708 27.246708 268.639210 301.183774 ellipse s 0.100000 slw [] 0 sd 0 slj 0 slc n 15.877903 8.871040 m 15.386146 9.136888 l 15.893879 9.370784 l s gsave 20.878100 8.878440 translate 0.035278 -0.035278 scale start_ol 2752 3008 moveto 2752 512 lineto 3660 374 lineto 3660 0 lineto 249 0 lineto 249 374 lineto 1088 512 lineto 1088 6592 lineto 180 6726 lineto 180 7104 lineto 3559 7104 lineto 4444 7104 5039 6958 conicto 5634 6813 5992 6550 conicto 6350 6288 6503 5922 conicto 6656 5557 6656 5117 conicto 6656 4783 6582 4481 conicto 6508 4179 6342 3924 conicto 6176 3670 5905 3474 conicto 5634 3278 5233 3156 conicto 7113 512 lineto 7872 374 lineto 7872 0 lineto 5580 0 lineto 3599 3008 lineto 2752 3008 lineto 4992 5107 moveto 4992 5532 4908 5806 conicto 4825 6081 4642 6240 conicto 4459 6400 4172 6464 conicto 3885 6528 3483 6528 conicto 2752 6528 lineto 2752 3584 lineto 3509 3584 lineto 3922 3584 4206 3669 conicto 4491 3754 4666 3938 conicto 4841 4122 4916 4409 conicto 4992 4697 4992 5107 conicto end_ol grestore gsave 21.909636 8.878440 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 22.266799 8.878440 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 22.623961 8.878440 translate 0.035278 -0.035278 scale start_ol 5568 2880 moveto 5568 2112 lineto 512 2112 lineto 512 2880 lineto 5568 2880 lineto 5568 5056 moveto 5568 4288 lineto 512 4288 lineto 512 5056 lineto 5568 5056 lineto end_ol grestore gsave 23.438200 8.878440 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 2151 -128 1991 -60 conicto 1832 7 1717 124 conicto 1603 242 1537 398 conicto 1472 554 1472 736 conicto 1472 913 1537 1071 conicto 1603 1230 1717 1347 conicto 1832 1465 1991 1532 conicto 2151 1600 2333 1600 conicto 2516 1600 2672 1532 conicto 2829 1465 2946 1347 conicto 3064 1230 3132 1071 conicto 3200 913 3200 736 conicto 3200 554 3132 398 conicto 3064 242 2946 124 conicto 2829 7 2672 -60 conicto 2516 -128 2333 -128 conicto 2624 2048 moveto 2048 2048 lineto 1747 3712 lineto 2258 3846 lineto 2462 3899 2645 3987 conicto 2828 4075 2965 4235 conicto 3103 4396 3183 4644 conicto 3264 4893 3264 5267 conicto 3264 5641 3198 5905 conicto 3133 6170 2994 6338 conicto 2856 6506 2644 6581 conicto 2432 6656 2132 6656 conicto 1871 6656 1672 6591 conicto 1474 6526 1322 6428 conicto 1088 5376 lineto 640 5376 lineto 640 6940 lineto 1052 7046 1466 7107 conicto 1881 7168 2372 7168 conicto 3576 7168 4188 6701 conicto 4800 6234 4800 5294 conicto 4800 4941 4704 4619 conicto 4609 4297 4413 4033 conicto 4218 3769 3921 3571 conicto 3625 3373 3228 3263 conicto 2767 3136 lineto 2624 2048 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 31.055400 13.988800 m 22.759874 30.162670 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 31.055400 13.988800 m 16.092029 28.341885 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 31.005400 14.013800 m 19.849463 17.962499 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 31.005400 14.013800 m 22.826118 16.917981 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.108289 16.552501 m 22.720759 16.955391 l 23.275589 17.023681 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.040500 14.003700 m 25.158774 19.659906 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.265294 19.210629 m 25.078187 19.737403 l 25.611870 19.571024 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.015500 14.048900 m 27.537084 20.836105 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 27.491653 20.376613 m 27.486092 20.935602 l 27.936620 20.604657 l s gsave 22.080400 18.163800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 22.557452 18.163800 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 27.555400 22.163800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 28.032452 22.163800 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 27.980400 22.438800 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 22.480400 18.413800 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.898039 0.898039 0.898039 srgb n 12.847500 23.762500 0.212500 0.212500 0 360 ellipse f n 12.847500 23.762500 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 12.847500 23.762500 0.212500 0.212500 0 360 ellipse cp s 0.678431 0.678431 0.678431 srgb gsave 18.885800 19.165300 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 19.698300 19.360300 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 11.550000 9.150000 m 19.390600 18.049700 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.498039 0.498039 0.498039 srgb n 11.600000 9.150000 m 12.847500 23.550000 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 11.550000 9.100000 m 22.640200 30.183500 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 11.600000 9.150000 m 15.902900 28.310800 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.498039 0.498039 0.498039 srgb n 31.000000 14.100000 m 13.060000 23.762500 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 30.980400 14.070700 m 23.746566 17.993408 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.968644 17.588589 m 23.648283 18.046704 l 24.206991 18.028124 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 11.600000 9.175000 m 12.270915 16.845044 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 11.988039 16.480109 m 12.280658 16.956422 l 12.486137 16.436539 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.590400 9.192830 m 13.315632 16.749802 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 12.985502 16.426985 m 13.340516 16.858801 l 13.472960 16.315700 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.565400 9.117830 m 15.336670 16.319709 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 14.935114 16.091784 m 15.388535 16.418755 l 15.378059 15.859836 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.590400 9.167830 m 16.943011 15.274644 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 16.499130 15.147498 m 17.016706 15.358722 l 16.875139 14.817927 l s gsave 16.652900 16.842800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 17.052900 17.092800 translate 0.035278 -0.035278 scale start_ol 1018 2750 moveto 1109 2801 1233 2858 conicto 1358 2916 1494 2963 conicto 1630 3011 1766 3041 conicto 1902 3072 2019 3072 conicto 2194 3072 2340 3025 conicto 2486 2978 2591 2874 conicto 2696 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1905 0 lineto 1905 165 lineto 2304 256 lineto 2304 2132 lineto 2304 2391 2170 2539 conicto 2036 2688 1755 2688 conicto 1662 2688 1559 2679 conicto 1457 2671 1358 2660 conicto 1259 2649 1171 2633 conicto 1084 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 152 0 lineto 152 165 lineto 512 256 lineto 512 2752 lineto 152 2843 lineto 152 3008 lineto 990 3008 lineto 1018 2750 lineto end_ol grestore gsave 14.668200 17.562300 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 15.143200 17.887300 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 12.652900 18.267800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 13.002900 18.542800 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 10.396600 9.752030 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore gsave 31.452300 14.099700 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore gsave 32.086705 14.099700 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 21.982000 9.114540 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore gsave 22.366638 9.114540 translate 0.035278 -0.035278 scale start_ol 863 2752 moveto 948 3797 1000 3999 conicto 1138 4326 1367 4352 conicto 1452 4352 1514 4296 conicto 1576 4241 1576 4163 conicto 1576 3999 1000 2752 conicto 863 2752 lineto end_ol grestore gsave 21.982000 8.164540 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore 1.000000 0.000000 0.000000 srgb gsave 25.188700 20.923100 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 25.665752 20.923100 translate 0.035278 -0.035278 scale start_ol 832 7104 moveto 2176 7104 lineto 1770 4544 lineto 1228 4544 lineto 832 7104 lineto end_ol grestore gsave 25.513700 21.198100 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 31.042600 14.069300 m 30.205166 10.953816 l s [] 0 sd 0 slj 0 slc n 30.107822 10.591671 m 30.479044 11.009635 l 30.205166 10.953816 l 29.996184 11.139427 l ef n 30.107822 10.591671 m 30.479044 11.009635 l 30.205166 10.953816 l 29.996184 11.139427 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.004100 13.992200 m 28.005745 14.758465 l s [] 0 sd 0 slj 0 slc n 27.642422 14.851317 m 28.064952 14.485300 l 28.005745 14.758465 l 28.188754 14.969730 l ef n 27.642422 14.851317 m 28.064952 14.485300 l 28.005745 14.758465 l 28.188754 14.969730 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.042600 14.030800 m 30.748078 16.746934 l s [] 0 sd 0 slj 0 slc n 30.707653 17.119748 m 30.513011 16.595711 l 30.748078 16.746934 l 31.010097 16.649613 l ef n 30.707653 17.119748 m 30.513011 16.595711 l 30.748078 16.746934 l 31.010097 16.649613 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.531800 9.101540 m 11.237279 11.817634 l s [] 0 sd 0 slj 0 slc n 11.196853 12.190448 m 11.002212 11.666411 l 11.237279 11.817634 l 11.499298 11.720313 l ef n 11.196853 12.190448 m 11.002212 11.666411 l 11.237279 11.817634 l 11.499298 11.720313 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.578400 9.108040 m 14.063630 9.015972 l s [] 0 sd 0 slj 0 slc n 14.438373 9.002089 m 13.947971 9.270428 l 14.063630 9.015972 l 13.929461 8.770771 l ef n 14.438373 9.002089 m 13.947971 9.270428 l 14.063630 9.015972 l 13.929461 8.770771 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 11.558900 9.106390 m 10.208691 6.866437 l s [] 0 sd 0 slj 0 slc n 10.015098 6.545273 m 10.487332 6.844430 l 10.208691 6.866437 l 10.059113 7.102554 l ef n 10.015098 6.545273 m 10.487332 6.844430 l 10.208691 6.866437 l 10.059113 7.102554 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.117647 0.878431 1.000000 srgb n 11.564700 9.147620 m 30.813873 13.885359 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 30.377177 14.035338 m 30.922437 13.912080 l 30.496675 13.549827 l s gsave 19.557000 13.323000 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 1934 -128 1649 -32 conicto 1364 63 1183 230 conicto 1002 398 917 628 conicto 832 859 832 1130 conicto 832 4416 lineto 182 4416 lineto 182 4776 lineto 948 4992 lineto 1570 6144 lineto 2368 6144 lineto 2368 4992 lineto 3414 4992 lineto 3414 4416 lineto 2368 4416 lineto 2368 1211 lineto 2368 864 2512 688 conicto 2656 512 2891 512 conicto 3072 512 3250 538 conicto 3429 565 3584 597 conicto 3584 163 lineto 3509 110 3365 57 conicto 3222 4 3049 -35 conicto 2876 -75 2687 -101 conicto 2498 -128 2333 -128 conicto end_ol grestore gsave 20.034052 13.323000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 20.391215 13.323000 translate 0.035278 -0.035278 scale start_ol end_ol grestore gsave 20.748377 13.323000 translate 0.035278 -0.035278 scale start_ol 5568 2880 moveto 5568 2112 lineto 512 2112 lineto 512 2880 lineto 5568 2880 lineto 5568 5056 moveto 5568 4288 lineto 512 4288 lineto 512 5056 lineto 5568 5056 lineto end_ol grestore gsave 21.562616 13.323000 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 2151 -128 1991 -60 conicto 1832 7 1717 124 conicto 1603 242 1537 398 conicto 1472 554 1472 736 conicto 1472 913 1537 1071 conicto 1603 1230 1717 1347 conicto 1832 1465 1991 1532 conicto 2151 1600 2333 1600 conicto 2516 1600 2672 1532 conicto 2829 1465 2946 1347 conicto 3064 1230 3132 1071 conicto 3200 913 3200 736 conicto 3200 554 3132 398 conicto 3064 242 2946 124 conicto 2829 7 2672 -60 conicto 2516 -128 2333 -128 conicto 2624 2048 moveto 2048 2048 lineto 1747 3712 lineto 2258 3846 lineto 2462 3899 2645 3987 conicto 2828 4075 2965 4235 conicto 3103 4396 3183 4644 conicto 3264 4893 3264 5267 conicto 3264 5641 3198 5905 conicto 3133 6170 2994 6338 conicto 2856 6506 2644 6581 conicto 2432 6656 2132 6656 conicto 1871 6656 1672 6591 conicto 1474 6526 1322 6428 conicto 1088 5376 lineto 640 5376 lineto 640 6940 lineto 1052 7046 1466 7107 conicto 1881 7168 2372 7168 conicto 3576 7168 4188 6701 conicto 4800 6234 4800 5294 conicto 4800 4941 4704 4619 conicto 4609 4297 4413 4033 conicto 4218 3769 3921 3571 conicto 3625 3373 3228 3263 conicto 2767 3136 lineto 2624 2048 lineto end_ol grestore gsave 20.178200 13.522700 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore gsave 20.562838 13.522700 translate 0.035278 -0.035278 scale start_ol 863 2752 moveto 948 3797 1000 3999 conicto 1138 4326 1367 4352 conicto 1452 4352 1514 4296 conicto 1576 4241 1576 4163 conicto 1576 3999 1000 2752 conicto 863 2752 lineto end_ol grestore gsave 20.163500 12.711900 translate 0.035278 -0.035278 scale start_ol 2060 2752 moveto 1667 2752 1360 2444 conicto 1053 2136 906 1724 conicto 759 1313 759 931 conicto 759 588 915 390 conicto 1072 192 1354 192 conicto 1596 192 1808 312 conicto 2021 432 2289 717 conicto 2393 652 lineto 2099 271 1811 103 conicto 1524 -64 1157 -64 conicto 700 -64 448 194 conicto 196 452 196 916 conicto 196 1681 778 2285 conicto 1360 2889 2092 2889 conicto 2387 2889 2583 2739 conicto 2779 2590 2779 2363 conicto 2779 2240 2687 2152 conicto 2596 2064 2465 2064 conicto 2210 2064 2210 2311 conicto 2210 2376 2259 2482 conicto 2308 2589 2308 2622 conicto 2308 2752 2060 2752 conicto end_ol grestore showpage opengv/doc/addons/images/central.eps0000664016516101651610000001740313344612246016437 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/central.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 11:46:14 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 361 325 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -7.425651 -12.867500 translate %%EndProlog 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 13.750000 6.750000 m 11.032949 10.553872 l s [] 0 sd 0 slj 0 slc n 10.814984 10.859022 m 10.902170 10.306846 l 11.032949 10.553872 l 11.309037 10.597465 l ef n 10.814984 10.859022 m 10.902170 10.306846 l 11.032949 10.553872 l 11.309037 10.597465 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 13.700000 6.838560 m 19.556597 6.830029 l s [] 0 sd 0 slj 0 slc n 19.931597 6.829483 m 19.431961 7.080211 l 19.556597 6.830029 l 19.431233 6.580211 l ef n 19.931597 6.829483 m 19.431961 7.080211 l 19.556597 6.830029 l 19.431233 6.580211 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 13.700000 6.850000 m 13.700000 12.163197 l s [] 0 sd 0 slj 0 slc n 13.700000 12.538197 m 13.450000 12.038197 l 13.700000 12.163197 l 13.950000 12.038197 l ef n 13.700000 12.538197 m 13.450000 12.038197 l 13.700000 12.163197 l 13.950000 12.038197 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 13.725000 6.850000 m 12.136646 1.990702 l s [] 0 sd 0 slj 0 slc n 12.020136 1.634260 m 12.413110 2.031842 l 12.136646 1.990702 l 11.937855 2.187189 l ef n 12.020136 1.634260 m 12.413110 2.031842 l 12.136646 1.990702 l 11.937855 2.187189 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 13.762400 6.823790 m 15.970656 11.782302 l s [] 0 sd 0 slj 0 slc n 16.123215 12.124867 m 15.691426 11.769821 l 15.970656 11.782302 l 16.148179 11.566408 l ef n 16.123215 12.124867 m 15.691426 11.769821 l 15.970656 11.782302 l 16.148179 11.566408 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 13.748100 6.823790 m 19.136690 8.830027 l s [] 0 sd 0 slj 0 slc n 19.488123 8.960870 m 18.932317 9.020702 l 19.136690 8.830027 l 19.106774 8.552125 l ef n 19.488123 8.960870 m 18.932317 9.020702 l 19.136690 8.830027 l 19.106774 8.552125 l cp s 0.000000 0.000000 0.000000 srgb gsave 19.100000 6.250000 translate 0.035278 -0.035278 scale start_ol 3840 3840 moveto 2453 1971 lineto 3904 0 lineto 3164 0 lineto 2053 1509 lineto 936 0 lineto 192 0 lineto 1683 2009 lineto 320 3840 lineto 1063 3840 lineto 2080 2472 lineto 3097 3840 lineto 3840 3840 lineto end_ol grestore gsave 10.255000 10.057500 translate 0.035278 -0.035278 scale start_ol 2217 -381 moveto 1949 -1059 1695 -1265 conicto 1441 -1472 1016 -1472 conicto 512 -1472 lineto 512 -960 lineto 882 -960 lineto 1143 -960 1287 -833 conicto 1431 -706 1606 -233 conicto 1719 55 lineto 192 3840 lineto 834 3840 lineto 2035 837 lineto 3235 3840 lineto 3904 3840 lineto 2217 -381 lineto end_ol grestore gsave 12.800000 12.650000 translate 0.035278 -0.035278 scale start_ol 384 3840 moveto 3392 3840 lineto 3392 3265 lineto 1010 512 lineto 3392 512 lineto 3392 0 lineto 320 0 lineto 320 575 lineto 2680 3328 lineto 384 3328 lineto 384 3840 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 13.751800 6.821520 m 7.996715 8.630384 l s [] 0 sd 0 slj 0 slc n 7.638969 8.742826 m 8.041002 8.354407 l 7.996715 8.630384 l 8.190924 8.831401 l ef n 7.638969 8.742826 m 8.041002 8.354407 l 7.996715 8.630384 l 8.190924 8.831401 l cp s 0.000000 0.000000 0.000000 srgb gsave 13.990000 6.142500 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore showpage opengv/doc/addons/images/reprojectionError.dia0000664016516101651610000000350613344612246020471 0ustar dimadima‹í\[oÛ6~ϯ0Ü×”æýR7)ЇaŠ ØºgC¶[«,y’’4{ØoI)q,K¶£’NZÀÊñùHú|ß9Þ02o•)b)5Óìå)buë/ur"Ìöm*<­s³É©U/Ú»0Ù£BÂv÷ ãÜýç]ªå_p®8#o‘úwïž­I4ÿK/Ò|²¤^¸ôâåèý苚O="¦ ñ—Wãßàþjçg¼!/¢Äf"^¸ t®ï P˜EâL 0¦X‚9¯¼ˆÂp¦Ã¥›P­iššq2ÚtEÂÛÍb[O‘_âÔLtæÅqt_t¬ \>xÜÐõ,Ðá*]~— k ᄺ Bö0£J}î 6¸ãâY±yC0@\)‹#…ʈƒ¡¸Ä!{àÍÁKÌ0ÀÌh ËJÜ ]°pÑ„ï’2E3ÊpÁ-e˜ÙT\b ¸B}P¦lš¦Â‹‰ºã¨óú©CÚ ŽT™+Ü)u RÒ!a2¥ @. sxOɦt–‡¦”¡ì¸¸äìQ'0!0Ûß •6èlm gŸäü¬ÿñu¼ŠÂ†Ò¦ 5Éâ®"wÈPŠ‚Z$.¡rUÜP”"Xͨëf'ùY9ÇSn÷[n‚“ãT&€Á|ü¬Ðô+š" q–øø&ŽBƒ¯¸5Å Ó£¦HÌ\=Í•u5.u<³1—TÓ’@%Ìëp9v&𼟵¯Hj¤i„“tF0{!ª  £º$IÖF;JAÎèŽv˜âYcA€p.lÄ"U—Æç¦xhr»«ŽcSƒL rÄlw´ÓQ’¯œgeyì1¿¹£Ú‰>Þ8úL!X”ŠŽ£Q”˜Ûôe„AZdÅI×%få<Ë£SÞ¬æþ„Ÿh¥5`{Ø!;?)²ý !hjª!l7M$´Þ@ÙC6¼©ù§vYNœlªJOw¡dÏ®pÿ¤âæÉ‘ãÚª³ÿ(LË€ìóÑ·ñƒ3/LÆ£$}°çŠFŒ³þ¬ƒ;ú ï¹¼¼|kí¯Ö¥cxÂî¿h3Ðý@|Q0Ö+ÊXå'›y¿ 7ºü;­Øý;ã/;¦~+îÜŽìU{Ñ&Õ†6!Il#JJ:Ö&‡DMÐ+×®p倨ºÈ}jÓM¿âôÕßèdô«¾ým¼ðI§ä“P9‹÷Ÿ£`Ù½R! LÙ'„PÒl3¨èG¨J#³3¡*6•¡jO¨lA©8gÜéS+U†ÄãXN©ÙÛp噪{£¥O¥Úh/ybUЪì‡=ˆ”˜`Œ‰ÂÊÄ Ä=ˆUypbõŪñÕ&Š&6„mtzœõˆÄU OÍ{$ºÄ¶QñPV eÕy‘Ù™R[YƒRµ¨T¸¥â+§”u¬T’X`1¥@Á¨E6ÉZ¼~¥Šõ6ʪ^˪ªàÄê5‹UvS¨êÚxãÛ|”LeVl«N/Â$$©²;AŽ0²’Eq׿(G¤Ë»BUs,?éRÙ 0äòĵ?ˆv=Ù S,©Ûs‰X—×zšÜÙi)ÒÒ¨‘Dl—K"DºM£T"âN`Ý{•o ;ñwχ<:öoveþ~æü%5ʸøAëüò€ÎyÞbÏZHšK“%@Šv›3R@rjS&Îq©›Gyúáä©";U§ÝŸôÔ©Uuâ-\ÿ'„ª./°=!AÀ„ öp‡á ™ñŽ¡Óu¬“u,‡VD¯­ˆªëí¶"D Û>$PöË/‚w¼íCÐþòÑ),¥Ýö1L²_&¢œvÙŠ¨šc©©0›PkŠÃ'L•Ϋñ®N48¨©ÝÔ•¢¯µÑð¶ù>ÙÏŠýì½û‹)×{Råúâ?¨ÿ‡‰zMopengv/doc/addons/images/central.pdf0000664016516101651610000000730513344612246016421 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœ­V»’7 Ì÷+;  À/pl9T9:—¤àØüûîgf÷nÓ­«º-bðF£É¿K«RÿŽß·Ÿ·_¿xùþïM£öaå¿[~._~»‰/­^Äû¨ÍËÏ›4Õ:µØœ5´¼ßþ8”ÿù~[Öª-ÓVí: ½bÖ1{q…öP²i°ZÅF¯Ã&$ß~y•§ÈNÜ£ÂP¼E]W}ô¨6 ©=²†>ǨëÍ‘Z­×.El4¸ƒÖ³]ê@ÅC«îÌ_ãèS⳺²÷§d-˜K&~ÊbÀmj5¯fEûÄȲSOv]:HýU®2ù;€08“Ç*:4á¾·@ÍcWqBHzÓÚgép[%sÒ«CÒ\ê`³žˆúª­C¢^ÇY΋\íY,«Ê*àA&|éúÄé«Z[Y…uMQiu6FT4²6E÷Œøl§ÃµŽUºE” ùW¹:’‡ž=$ß»¬Ь IlÀ€L1Y»œ~W“jQ¤­VsÖÏv=Ó•j¯ztþU®~<’K³Õ†Ž4±:WV¢Y#HN\£‰‘£ÒppB @ª‚0 C²:‚iJÐW"ú®‚:ÞêRÆYgª ɼrI/Qe}±Pò2Û@ꜗû£Î§šÐ½[‰º¼ æä´Â dhʼn%M7(€÷Ä­„ÞŸá /o·˜ ZÅWƒË8Ó¥”èéu†êñKò~—`p=§¸:½Ü% 4W¿$xæLT+š—qm:gbhºä õH}0¨p`E´4? `ٰþÈ:l`]Ûp ¥™R†¯»Î ó ,° kY¨Å°½—ÊB¢‚«ãnó©é„L|©æÍþ°á¼`NÉû%‘œ $5 DÇñ ó,áNLM?<þy– !ܽÉL(!w¹Zl•LðIpÏïÛíkaÞ?±F‘ úEd¾²(Éa @XÛüHǬÅ1ÛêØÅŠ‘'uWóÙÍ‹:Üí\LÂ×#ƒW¹ü@ÂçÁä"y‡%.¸7¿$Àáä}¬Í|_`X{€¶9ð Ö@ €3Ød´{R8ê48î*÷/ ÚÊk|¡§ƒÍR–;àýpæ~ì§ #ÓCÐIk¡FáGŒ€/œ ½€‚MZ=v*F‹Á}ºÎ´˜ºéíÔ ¢èS‚Õ"µ–ܶÀ±m[àBúV:Ž`“˜¯NT†»Ý7à ‰B¯q†Är¹²zš*îmáÆ7øËÇ샯5T޶ӂœ‘gh0†ÙgZÈæôS#Àíè6ÈvAÏ.úö‘û‚KÑdwËôáŒÞLÛ‡„Ýt9£qd(x"Ý#YÝIqÔÊ5H¹ÄpŒ¤F\gZìVž4rí_‚ž¨ò}ø1Ÿì0BC༈|6÷æ~Ë¢£iqJFuÛÈUzàÃ3‘Ü7=`º‘À=õ¾õšN=7d#½ë|áó’à<ªm‡yÕÇal[ê>ãù}òšC ºG¶œ#ʼnÚ`2qKK<é÷ÖŽ½Œ×yî­½Kð¦;Cô‡µÿH o Äßoÿ“‡`endstream endobj 6 0 obj 1212 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:09:44+10:00 2013-08-12T12:09:44+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/central.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000001516 00000 n 0000003190 00000 n 0000001457 00000 n 0000001317 00000 n 0000000015 00000 n 0000001297 00000 n 0000001580 00000 n 0000001621 00000 n 0000001650 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<6F3A039CDCD2859D0ECCBCB640C8BAC0><6F3A039CDCD2859D0ECCBCB640C8BAC0>] >> startxref 3428 %%EOF opengv/doc/addons/images/absolute_noncentral.dia0000664016516101651610000001101413344612246021006 0ustar dimadima‹í]Ýsã¶Ï_¡q^°‹Ïªw™63íK¦í´é³‡–h›,y(ù.—‡þí]€’?$Ò²I‚5up'I)ÃøÔî»Àîâ?þv»˜|ÎËu±Z~<ŒŸMòål5/–×ÏþýË_~°g?~úîó"ûýs]f·ú‹åÚ?}<»Ùlîþðá×/_Øâë:Û¬J¶(îÙ:ÿðßl±È>P£gŸ¾›Lžv0Ï6™ÿlûi¶Ù”Ååý&Ÿ,³ÛüãÙe6ûõº\Ý/çgU«m»Ùj±*'Ÿ³Ådzï¯ÂÏÙ‡m7žõóBßwÙu~YæÙ¯Í]súq®M×wy¹ßííÝj]P“Í×»ƒ& ýø?i³mµ¦FËëOßÿœo6yù}5¬í‡ýÕ ¶hs›•×Åò‹ÞÏ¢zÀ:ÿ£…UÈÁàî½¼îrX¸Å°på°pÅúânUnʬØB^®V‹<[V¨›ò>o³že ±—¦%Ú÷~Ul6«#ã¿Êë×L úøAãÞª½×e1YyŸµhèåK1ßÜ\üéuU½Ôûçb]\.òºÑËMoÝí§ûýo'0øãŸw”†ª·Æ%bns•«·/×÷Å<_³çmzºÙ6ûpì­ï·{í‹©>Ú[°Ä"ûš—Ûîÿü¸TO¶_ð–q&ÙlS|Þ==y'«Ëÿä³Ív²ÿÚdËyVÎ'?L~.–ôW†™!ÅüãÙßùó·µ??êˆðàuÝ­d ,ÓFã¹pL+ ûoâGš`./÷QJšH¶¼^äHB ¤œœ"gFp8§¹æ-g«åò"_ÎÄZMó°) L+V»-ïogwû©Óà·tJkL~±Þ|]äû=ç„Wu-t]}X‰W{y]å ãê\pæTDYCÍœèq,ýw*ãÒÑ3ÊÊÈÂV;ÇÃfRÒ ¹öƒ’Ι“·þ^.é»!!Z,Q»ßLnHì<5гÉf奌Äíñפ½‡½×k?Ò ÙT2úâ-‹Ê£ÈŒ´ÆÃ©ìÔc¥ƒf Tl=œ`M#d–ƒó#šÛ$Ø‚ížËµH®±¹vÊ•ŽÉÚB3%„ ,mQOX[hyNŸk.\|Ñ>œãa3?HcÑJ¡RI¸„Û>n;pË®Â-IÜ€,>WºIŠ zeÅÔ£:yNŸ¢@Y¶ë§Xc¹ÐÚÂ…ñ£)ßsÓ,/²²\}i–í®=_,òåõææðkÜíp¦ºB„=Š.ýèŒêCg†Ð.‰j dTFçq0ny•ƩȤ1§ª1º òd"j €pÂ'ÆÚ 1ÖòJcÔú²?Á¦V4>—TeìªòKþÛæ‰ªˆ­ª˜öˆÈĶÁÏTc®0;$’G£pŠ–qå· -­4m‘7þµÙßkÓt¼0ŸµÛ;ïÜ4u¾p>ÐtØ´Znêüç“«ì¶X|ýxöKq›¯'Ë¿Lþ¹ºÍ–g“àn­O4YuZüðçÕbþ”Þ>œ›¼¸¾©ГÓ"9úŸ1Î:ÒpÙ ó¹T¾I2ÛÀ=?Ei¯%¯»G¦ê£¼¯ñòœ]D­T°EòK4Iž/ñ ž©@øR‰©S½R2S‘©di“2xÄ‘™j‡„aœÒ³¼•˜*1Õ«%31Õ™ªsø,ø]¿r‘e#¢zHœèm*³µ©€ Sœ Ÿ}d&¦#Sé’¸Ïù÷–Md¦Ú!‘U˜ }À°©Ì(˜*ú‘T/™‰©ÆÈT¦‡u·õÉ@ÄÞQß6I$ïOr†Ûu9Šõè??5Êcâ§1òS÷8[Þ¦à$“"_T!!JMéÑ© ØAj÷oß"= ~Ì×$Ž)iŒôÔ=¸Ö‡­8G`•ˆIO;$NŽžÑSzÖÚd©Û"ÉO_? ÀOMò˜øi„ü„Ý‹c“»/ÂÅÖÚ¨˜ÞÝÈ0´§ô¨Bȱc‚«8w¿'v nWƒ4&r#9‰²¸/Õ­«@4s”§%ëoÔ$'}Iœ4'Õaâ£fJ"ôÀGRÉP©[™¨[MÜWŠ×¡~¥2án6T§į)Q;ËgBl¯nEæ$ØÑe~ì_ô™2?þ_9YØ9žšdQ;!ãR£FÄÅ”A¸P1ÐÄÎ^>˜^mà®TÆU¹”ÒŒN3ü*%b½u”ãPG#ý­W`!è#w”V%§Þ‡BZ…¡l¹n½ù›2)äßQõ¡qõÑ[ƒ:T÷@N룯íB¡FÞú¾¥7éãuô å?’"&El»©Õ=ôS3ãW)CFdÔš[Í´žz_N@UfCŽ VásJ¤4‘¦^&£msíóYÚæê‘¡:‡|YHWq…ŽIP[ú5ÊS”`¥4验˜þ©L5Fв=Q²rõ1¶p\ÏPŒ(é·á“•Œ¨×Èdb¨12”ëÁˆ²âŠÈFT€Af·F”2&ÀÚQQ)»oh#ªF*E¢$ï!6]Véu*n\º 5žñ*ܾ2:YPÉ‚:.‰œÆHNc?‰)x7Òª‚æ\`'•ƒÇQ¥„ã”pÜ(ˆ‰•ÆÈJ}ÔæRØèùpüÊ—BV¢‡U#0›>þ8,1ý\\æe¶¡ïzòœŸø·ÑW/’CÔŸÍ&‚ê‘ :‡ÁS8-«ËL̬™IYN>fœk Aɨ94é¶±8qˆRö‡èk§ÄÜ÷v’Åj[\*,´ ÙÆ„$ñùk¶b}’+ja„µ)&1Å$¶µºsÆ… «¹Qq‹¼í “Æ_›â‹ÌC0¸C‘·´%<¬wÓ$™ifŒþî©Lâ c#3•ÙJ5BšÀT õ çŠt´>è>q“d&¦££Ó=Ššì{'_hõx„Iz°©Hôå9(¦¸~}kÓ<ës$¡ÉtMdòwjuó¯ùê6§¿š‘rþ#/¯üo~*ÊÙ"¯3(l…¾Ö…‰kK å;”×NkC‰!Ñöd›ÞOvÌŠ˜³MËï{‘ß’:”˼ŒøÞÊQ’ ÝãºØÙ -ðÉÑ©‰ªÖÒq!´€Žäu¤ÔI{öº*‹È뢗Ëlöëu¹º_Î÷a.W«Ež-+ MyŸwxWÁ,mæa~°€=1*[¾¿Eqwq³*‹ßÉ^Î/Nî*[¬ó0Ä›bd}¹¦îó³Ö/©'O²{€¶cÄÃÎב‡˜æÙÈ'Wú2¤úàa´…Ò‹¼Kû]ƒ&‘4Heª87Âí.Å{°N…5AÈ•ƒ¸&j…d™Ae,)¨¸"²AæL`(µe(°cHÇMfÔàfÔP&‚áy¡ê£€1w¢ ä‘÷£´•êÜ1é@ÙØ ª"Þ]üØÈÚYÖ.ßÖRS‘‘¯Ù¢–éòÿ_‘Uõ ‚*á"WfÕ>4…La-ô™z,—0@4tí4kšÒ¸ü ÛÆ†GÑù¤6½ªAeñ`¶;[Ýk±«ô/Ágc±@­+îC¸¹Ñ LR–ÓU݃²@ì2ü–iiŒ¯¡`¹Ö^YP(W•ýV¨ -ÃïcÇC‡¤)'š£Lšâб•’ë¸ÖX…äï÷« úšÜ2Ôl3| U‘îÒ½sd¾4 d:bã¶í!³?$ظYýUø’#ÖA8jKœ”j!5Ê`Jã#uŽžDÜTË¢VAª@ 30¥ÿïduƒ‰I|”ø¨Q SᣟiÞC’ÕÎ3\‰˜É< ˜æNœ¦3%dÚxd#Úû~}º]ÓñuäsLCMcC©l0v€‚vµó¬½N¬ ãhÓfÁÉ*íEy0T ×Fٸʸ_®EP‰ÂòèAŠAÖN³Vwø„“IwNUw\ºc rµt±+©ªª½2ÎNCªdUoÂqnâ+Oýqâ„@ ˜>}z%‚Ë`0 ¾æNNNE2* ·oßþöÛo ÓåÆ`0õ®æE“õfffŸ}ö€+VÈårS¥Å`0õ­ŒÍ2-]ºtÙ²eÝ»w_µj•éc0ŒúVFx{{s8œ>Ÿ¿aƈˆ“¦Ç`0/:Åõç»ï¾333Ю]»Ù³g+Š÷Þ{Ϥé1 Æ‹NñCýŒ3úöí[tbÕªUnnngÏž=pà€‰rc0Œz€VF}}}¿üòKÝ666«W¯°`Á‚¼¼<¤Æ`0õN%6£DÔ§OŸ .,^¼xíÚµu™ƒÁ`Ô*“Q<èܹ3ݺu«}ûöu–ƒÁ`Ô¸•Ÿöóó›;w®R©œ7o³Çg0Œ²TÑ ‹[·n””´wïÞ‰'ÖMZ ƒQ_¨¢7 ÀÚÚú«¯¾°páÂr×Ý3 FC¦j0iÒ¤>}ú¤¤¤¬X±ÂØ 1 Fý¢ê‡z >ìØ±#…‡‡wèÐÁØi1 F}¡Z½QmÚ´™?>›kb0ŒRT·7 @,ûúú&&&îܹóí·ß6jZ ƒQ_¨Œøõ×_ßxã —ÈÈH;;;ã¥Å`0õ…šÉ(€~ýú;wî½÷ÞÛ¼y³‘rb0 Ba!6mBA5±cØ·66¦Î‰ñ2RcŽŽnß¾½R©¼yóf§NŒ”ƒ¡'R)† Ãøñ˜9ÙÙpp@h(† 1uZŒ—‘êN1áããóþûï«T*6×Äx‘yÿ}…˜9ìíqÿ>6uNŒ—”Ë(€åË—7kÖìÊ•+?ÿü³¡óa0ðñÇàpÊÿâram&Mл7.Ä¥KåGxúÛ·cÖ¬â#~~0ÈfŒ‰‰Xº}û¢E ØÚB €ƒºvEp0ž=3@|F}¤Æõ~ûí·qãÆ9::FEEiœó C!ãþ}\»†… ‹¨TÈÉAx8´Ç{öÄÞ½pw/aûv̘äd¸º8·3gп?„BŒ__¤§ã·ß™ ffؽcƸEF=€jËàÁƒÌ;·ÖŒJˆ' øëرâS*Ÿòñ!©´Ä½ë×@I‰[ ÂéÓК5ÅGÉÑQ›‰…%$¦!F=¢6õ6oÞ,‰¾ûî»7nNÕŒªárñÅ(z ŠŽÆo¿•¸Àß.\• ›7#=Ý ¿nܸ¸ZP€C‡ Ù£^P{õòòZ¸p¡Z­~÷ÝwÕjµsb0ª„ÏG»vÅo¯_/q¶gO¬\‰÷ÞÛoâ¿ÿÅèÑpq1L»cÊ­LáéYüúÉÃ4ĨGÔ^F|üñÇ-Z´ß±c‡¡b0ª‰PXüZ¥*}ö£ðø1öîÅW_¡I“ ƒÌ›Wát–î× AÚëÛ´ÁO?A$*D©,~mf¦×‡bÔGô’Qssóõë×ÎÈÈ0PJ FµHJ*~Ý¢…éò®^-~ݵ«éò`˜ˆZÎÔë2lذÐÐЙ3g†„„$'@B<<Šß;†aÊßÞ»‡Ž¡ùáåppïüüjÓJ~>¤Òª/ +\u↠Ófâ鉇Kt“ ÈèãÇýüü ÅåË— ’ƒQ®ŒªÕÈÈÀùóX¼qqÚS|€ ê:½Œ üñŽñcÐL ¸¸àÔ)°Ë QŸ~úéçŸÞ¥K—ëׯóx<ý2¥d´\ðÑGøàÔÖ׈ лwqo¾‰?F£FuãEÀ02*•JýüüžÔ«TèÚ·okö쉿ÿW‰Òyóðí·U_6p Nž,}°eK<}Šìl0ÏÈŽ^3õº >|øðáÙÙÙË–-3TL£<BBŠuóâElÜXã ÉÉðôDZš¾Étꦡ ÃõFÄÅÅùúúJ¥ÒË—/wïÞÝPa “JfêçÏÇ–-Ú×ff¸}»föß|ƒuëðô©¾#ªj5ˆØã<Ãp½QM›6]²d ½û²õÐ †X¹k_Ëd˜<¹D|•ÄÅaÚ4}54.o¿þýñË/zÅa¼RFûøøÜ¹sgÛ¶m†¬?<صkWaa¡©aè‹ 6m*~{ó&V¯®Áí™™˜1CßFÂÞ½øûoLš„k×ôƨ×XFE"Ñ–-[|ôÑGÉÉɆ ®'m۶ݶm›§§ç† òòòLC/ÆŒ)aeÿŸs§ô5……X·ŸŽï¾ÃС(ú7Ÿ6 nnzµ.‘àÖ-ík"œ;§W4F½Ç¶Q#GŽ0yòdcׇ ÏÀÖÖvñâÅñññ¦ÎˆQtù2­YSÂ(oÖ,:y’’“‹/{ú”,,Š/hÓ†öí£¨¨â }ûRHQVjÈ$›5+núèQCFfÔ;Œ"£±±±–––çüùóÆˆ¯#FŒ(ú"&MštçΣ¶M—.µ…—ß~+! º_C‡–¸²”Ôäâ¢=5s& T|åýû¤V2É+W¨M²·§%K –Q1ŠŒÑÊ•+h‰©‰ÚÁçóKuÉ_{íµ?ÿüSmØß3¢'OhìXâr©ys’É ›QOž—KGŽ˜:FÃÀÀc£E,^¼¸U«V<غu«‘š¨­[·ž3gN©ƒgΜ^}kײ‘i(ÚDdȨTøö[Œo0|£F숉‰i×®O$âJ«ãìXCìííù|¾µµµH$²°°°´´ …¶¶¶|>ßÖÖV(ZZZZXXˆD"kkk>Ÿooo¿PwÏÉçxyymذaøðáµHãâE,Y¢ÝÊÂÅëÖ¡kW9//ŒˆìÜ __LžŒ¨(üôZµÂÔ©%^?z„;àíéÓ‘€'àîŽ!CšŠ‹áìŒÞ½!#:ÖÖðñÑóÛöò³j~üpwÇüù•à3zR3ÍÍÍ sqqÉÏÏÏÊÊÚ°aC›6m*º><<<  É„w¸Ÿ|­¸{÷Ãyo›EþcÆçÙÛÛ››››™™•ýo¹§Ê¬õgž:uêÏ?ÿ¬{ÄÆÆ&88øý÷߯EØ‚LŠ´ommˆ“'ñçŸ2ƒãĉZ¾4þ‰“'1x°Ö㯿0höõ©S8௿†éÓѯ¶nÅýûX½]»âý÷‘˜ˆ¿þBË–èÝR)ÒÓaokëZç F9Ôà¡þèÑ£3gΜ2eÊo¿ý&‰òóó [‘Çh||<çÖí³,­D=ú¡G?V\t5C ÝÌà+D¯HŽ‹‹Û»woÑ[33³ ÛÕÖaÂÂk×ÂÝ?ü±¹¹xø ];,] oohÝkÖh7ºhÕ kÖ eËÒ¯½½±f ¼¼ IÌœ©5vvÆØ±‘]ºhmÞ5sV–†èhhþœ=~Œ}ûPP€÷ßÇ­[˜>Æ¡woœ;‡aÃ0dBCqþ<Þ{ÇãË/_E—.:È˃‹‹ ì;ŒzL5gô·mÛÆår/^\täÔ©Sšɺ%Ñ%ѬhšÅá¤;¹:öÓSáC“¨Ù3júü«U,J¦ÕYtIJ2—•Ï’%KŠ>ûèÑ££££ Y"¡òöÖ0ººÒ§ŸRv¶¡ÂW†XLôä Ql,íÙCgÏ]¿NS¦ÐæÍDDGŽP“&4kÑîÝÐĉDD¿üBOô¼`sÔ("¢3ghÐ í½ JÕÅga0êÕ’ÑÐÐP.—¨T*‹fggÏž={ûöí•Ü à /¯¢òhé?d(ét­Î¢¡IÔ\GR[>£¡I´:‹NX¥ï+—ÜÜ\[[[Ý»w¿|ù²1šP©èèQêÚUû‰­­iþ|zÑVKåæÒ;ôð!ÑíÛ´líÝKD´{75nL mÛFÍœID´c4e Ѿ}äåE«V=zD{öÐýû¦ù Æ BÕ2š——רQ#§NªiôI“&øqúô"-ärµ=%""’¨è’”VgѨdj[¾¤æNRׯ_ߺuëC‡¼Ò¾*ýñõè¡ýÜ^‰X$%щZ‰<|˜úõ£o¾!"úòK´KwÖ¯'€, "úáòñ¡¯¿&"zø¦§OM”:ƒQ·T-£«V­àééY‹è½{÷°{Ö,TEëõ("¢ìÅu±¤zêHj‹g44‰>ͤãù”­Ÿ¤ž:uJ·C]ܽKo½EŽŽ”“S—Í‘‚Š‰Ñ®m?vŒ&N¤ˆˆ-"€¾ü’ˆhùrhùr"¢;hÈ:tˆˆèÉŠˆ ÂBSåÎ`…ªe´}ûöfÏž]‹è^^^Â>ù¤¨7ª ;9QÅ#ªD”¯¦KRÚMSÈ«¤¤öK¤à :žOYÆyð7™™¦ÎÀøˆÅt÷.%$íØAj ;¦M#€¶n%"zï=híZ"¢ƒéÓOéî]ÓeÌ`ˆ* žär¹¦ý›o¾y÷Ýwk:eaa!•J%ÿþkùƸw/ÝÊÊY"‰çr=Ôê\//Û;w`eUe)áár„IqS¹N¾Mù2ƒ¿^1ƒ3!!‰ÇÝ»hßÍš!8¿ü‚íÛ1`FÆáÃØ·&`Ú4\º„o¾ÁÀ¸{ðöfÕŒzCOiÏ7¬©Å.u™™™R©ÔÖÖÖÂ×·pÂÁ½{)¶¶Î‰ŸŸ*¸ÄÄ`üxüñÊ…”œƒD˜c%!¢a2„I.Gœ¿Hð‹БÔî"46ââ,FÍðð(Þ dͬY£}=mZµB·nðàbb´ 7-ÂÙ³Ú-CBBÀáàõ×ÁöHd¼ÈT¡7šºD ##£Ô©¬¬¬‚‚ww÷ŠîMHHàîî®*(ˆÞ»·-ÀMLÌíÔÉö΋™3±?NœÈ~ã {{G5Óå 턘c%¡@˜ 7e¸QFRýE0CO3¸3I}!:C‡j__¸€‡µu¯£ystì6 :ݺÁÙãǃËÅW_¡iS( M–9ƒQš*û[µj`àÀºÇŽ›žž^É¡¡¡ÚÕj%G€xºmR>ÿÒ’%R€ÙgŸé90AD…D÷ä´#æ¤Q»¸â±Ô¦ÏÈ?žæ¤Ñ^1E½XŽ}ŒªÙ°¦M#¹œ”J²° ‡²²ˆˆ<<È×—RRˆˆÎŸ×¾`0LEÕ2zðàA‡`áÂ…ÑÑÑ?Þ²eË€âââ*¿1$$ÀôéÓ‰ˆ¶n%ÔÇ_²±!àVŸ>_vê¤æpˆÃ¡]» òa4(‰¢´WLsÒ¨}Å’Z'Åþ àVSd$>LD”™I––dkKj5ŸO|>}ÿ=]¿n`{f£Jª[~daaammݹsç 6ȪáB¼|ùrË—/'"™L&ž3‡€ëýû_ûþ{5‡CffªgÏèÿ#@Åãž<©ïG)•ޤv,)©]âiNíÈ£{r&©õ ¥R[”úìuëFþþDD11Åî÷yyLüa c¹ßÑ´iÓ„„„Ñ­iÓž6mJÀ9 55•Æ# {Ü8" õò"@*Ò½{ÆKFCl!íÓûéÔ-¾„¤vЧ©©´5—îÉ©þ”Q1JMo½Esæ9C=~L“'Óþý¦ÍŽñ2cD£¼ž:u*44tÈ!‰49}€B ÈzüØ*=ÝÜßD¹W®¤X[§öìÙ';îî¸zÏY–8¥vzêšI:»œ[qÑQˆ s™¡­ÐÐ[§2ê„G°oÜÝ1mvìÀ;ï`ÌüöÎÃêÕ˜4 “'›:EÆË„ñºmÛ¶þùç"¢Ë—i×.ínŠ7oÑ_d HD*‰„ºw' «E ‹—REÄÒA gÐ+ %z©¾q41…¶æÒ )Ø“ýäéSúæÒ }ôQñJÖíÛéÕWµK° }0boÔÎÎ.77733ÓÁÁA©TæççóßyÇòàÁ¿† šyçŽc÷î(,Ä­[èØ1=""ÏÏÏS­ÎêÖÍ!,¬ÊbR㑪*.õTX|Ü‚ƒÎ"mUW„¬8¼‡sçС:uÂ[oaÏ|û-æÎÅ_àÜ9ü÷¿èßßÔ)2ê!Æ’Q±Xlcccaa¡Ù!îÉþýykÖØ -nÞ<ÈãýG*´`góæ¨V­ZEFY²dâ7ßXK¥˜>Û·#«š’¦ÂÍç’Sˆ¢ï”9m…!È"ˆ˜¤ÖCRSqíüýѤ qý:þüƒaölÄÆbÕ*tîlêõcÉhdd¤¯¯¯··wtt4€´={½õVvëÖö‘‘b;;^b¢……ų›7»vµâ÷ï÷7Žˆèúun¿~((È^¸Ð~Ý:c$VkÒU¸!ÇMÂåx (–T3üžKª¿fLRë!éé8}#FÀÒ#%QQðñÁÈ‘Å¶Ü FEKFÏœ9Ó¿ÿ>}úœ;wÒÒpìš5ÃøñÈÊB\œf…`XïÞA. gO\¸ ½qÁ‚>›7sÕöíüéÓ‘›þdªpGpÂdøWõóã|ÀW¨]“ÚMk6?UIIÁµk9¹¹pr—‹Œ XYaà@tè€+ð|eƒñ#¹þôÓO&Mš¤y«V«Åbqjjj~¯^ј­QN98ýÛoš[5òÕÜá´î?·L-×…Zãï—ê¨ê'‘‘¤ùÁ¼Ÿrs#µš$8Ö­3urŒcõ—ŠÔ©uLÏž¹AAb??9'NhÛÚ&L˜ ýw@ÀÜÜ|Vd$,@a¡bÄõ;FÊÐPXqd†`{wÃìuÁø‹î+ð“sÓÑ)¯%aY&B £®:&ã¡U+ŒÞÞ8{7‚ÃÁùóøë/:qqX²—.™6M†©1’<Ïž=À–-[ŠŽÈ,- (Ø»—€/¯"ÿù´§OS8${ö߯R]pv& ×ÚšªZuúb"ѱLÕu¡n®c™šÉz©õÌLÚ·~ÿˆhËè7ˆˆîß§Ý»Ùÿ†ˆ±ÆFGŒqìØ±#GŽŒ9R{èÀXX 0nn]d6·xqÓuëж-îÝWÛA¾}ù²`ðàvb1üü[[cäY7þ­Ê2•ùûÕGnݾ}èÛC†`ñb¬[‡eËðå—xðZµ2u~ŒºÁHòÜ©S'7oÞ,:"‹SRR¤R©¤U+öj,K4Èåê-øwÙ2Ý ª´4jÕŠ€ôvíH.7RªuŒTM7d´5—&¦Ol‰jÿ z?öŠ)m³QÙµ‹ú÷§«W‰ˆF"€vî$"JIan)/9Æê6jÔ(===))ÉMÓ÷nÏkqîœ`áBቿÿþ½‡Ç̸¸¢ëϾõV¿={’„B·¼<ŽHTt<îüy³¾}eþç?Ž¿ÿnŒTMˆ®eêu9$:æE–©¯šÁƒõRë#ƒñï¿hÒþþHMÅÉ“hÛÖÔi1ŒƒQdT&“YXX©TÊ}þž4ztãÇ“–.µoÕÊ|Ú4qPµÎȼT"Isum–ŸOß~Ë™;W7Ú7“'ÏÜ·OXXˆ+°|¹Á³}AЕԛräéHj#^q]ªÀt)2j‚R >yyhÝb1ÒÓ!¢}{¼ú*Ö¯gUS/F‘Ñ'Ožxzz6kÖìÙ³gÅGoÞijgð÷‡fÍ`g‡ÌÌ¢‘P8xcÇ’««**ŠocStX­VsBC9¯¿µ:oãF›ùó žð‹† x¨ÀM9Âe¸,+1¹¯‘T3ˆà'+öñQ«ܺxz"&¹¹X¼'¢woSçW?ÉÈȰµµ^Œn…1F .\¸à•W^Ñ=(—ËÓÓÓ³²²ˆ(ßÑ‘€_þûß·©Õžž\3¦lÌS£GPÈá¨þüÓ9¿°èºPw(i™Ú™Y¦Ö7¢¢èÜ9"¢Ý»  Þ½‰ˆâãéÔ)ªÛ¿ë=;vì?~¼úÅu6JÝhé¢Q@ò_%õí›8m€TOOy'O–¸Ãy0v,ߣG‘—W*f·Üߤ Ÿˆ;nîÞ5FÚ/&<ÀG€‰VØêŒ»¸Ô«1ÔŽ} [7,_Žyó`×. ÍÆ»¦L¯qçÎýû÷¯\¹ÒÔ‰0Žfbb"ÊȨÐþþý&‘‘œFŒ0Ý×·Ô¯®Z•Ù®µB J²±±ûìÆŒXœß»7t¦§MùZI½í®•ÔQ–hÌG¦ g¥X“aÉð‹Ç›©Ø–‡›r(eàÅÐ oo¬XÑ£ÀÁmÚà?ÿ€… áå…Ó§M›]= <<À§Ÿ~úã?š:ã<Ô/X°ÀúõëKÍÉ¡C‡´õ 7o@ÞÞ……eJ{ …y11e#«òóïXYáêJÙÙÆH¾žR¡ej,³L­OtîLÝ¿OD´p!­[Ç~ÌËA¡P˜™™iŒÏ燆†š6£ÈèèÑ£ì/³oCzzú³gψˆ åB¡8üÝweo¿Ù¨WJ­qùèÑ8 íÀR5¶„j€¤(éx>gPPIImKShC6]’’œIê ‰ZM7n¥§“@@¥¥>lCóMW´ssóK—.™0#Ž6iÒ¤Ôñ”T}ûʲ³Áç'»»sÊ8kÖ¨nááˆ/{ö•áÛܻœ?Ÿ:dŒf;]qáa¨V;âRÜpÇVgL´‚·„06æâÍT´Çè¬ÉF˜¬Äª*†iáp¶¶8|«VÁÙ`Ô(øúB¥Ô ~𻔌J¥Ò‘#GFFFš*Ÿº›bÐ<>¾å“'ê¤$<ìí]öö.S§rÇã*ªÏ?/7>×ÓóÑ×_ç.çÎe5€ú'}(’Ô3ΘjvBÈárlËÛ©h‡aÉX“3ÒK&D À°aX¼¤Rôì‰!CÀãáôi´l‰mÛLŸI¹uëV©#™™™ýû÷×( 0xÿ¶°°Çãq¹\…BQúÜ_Ñɓڇ“ÐP”å ©##U\®H® ¯®V«7  âr  ­[ üéJ:] õ÷kVÆßou. <æœò"¡©ˆzï=èÓO‰ˆNœ ~ ¼<“¦e :W°3A@@€D"©û| /£ñññ\]]Ëž’H$ñññbŒfg«9péôérãœkÑ‚€È.]*jH¥RQHˆf›{ñÁƒJ¿!’¡#©º–©-˜eꋇZMçÎQBQ¯^PHQzºióª;¤Ri%U÷C† )·gfT /£W¯^àïï_öÔ?sçF{{Goܨy›doO@èG•çé… *€¸\ºs§’æÂ^y…€|O}ë–þÉ3$Ï]¨G%SËØ’Zäï—Å$õÅ`Ï0€òòH­¦Ö­©CÒÌà¾Ü\¿~½ò'ì麶Gu‚áÇFË-Õà {?zdó䉿­ý°a†ØÙ•§yϞܹs¡V'͘QIs-øÓÑÑBiÆ*ð IDAT¥â †ØX}³oðX>w¡>äŠ{Øë‚÷md. ñ‹sÓÑ1¯&j]¨³ØXªéxóMüõ¬­‡Œ dd I(˜3çev’Ö_²¶¶жmÛÿýïãÆkÑ¢€;v¬X±¢Ns2¸0oܸÀ¼yóÊ9A§NiHˆè§Ÿ PQ¨‚ØX1‡CÀ£]»*iQ%•Rß¾d¹¹QV–^Ù3* _Ç…Ú«Œ¿_p”P"ó÷32=x@DtàÔ¡‘XL¦ÍËðL™2E£]-[¶¼{÷®H$âóù999š³éééþùçÊ•+=zTg)^F/^ `õêÕeOI¥Òøøøäädíû¨(R˜ò*í5œîÖ€üò†t‘''? HnÕŠ“›ËTof™ú‚ñìý÷¿´{7ÑÆdnNÏGÑ^üüü¤¤¤QŸ>}ü®ÙÀDþ¡¾¢¢Q™/ôí›ûÆÚ÷ÞÞ¹"Q# £âÁŽ>'NÀÁÁ"<gÎTÒ¨ÐÕõáúõYB¡kT¦LaŤFÅœƒæØ`¯ 6Åq7Û#È fÄ)q8Ë2ñJ"07¿H§4uÆ ‰fͰj&M€G —£Y3øáìÜ ¹Ü´ÙéK~~~DDİaÃþþûoýû÷pÚ´ëg .̯¾ú*€s›’d_¸@@^Ó¦EGTÇ»„W€ìÓO ˆ¶µ­ÒC\uãYY0eJí’gèC!Ñ=9mÍ¥©©Ô¶¤•<ÍI£½bŠ*SÇ0*±±¤T’\N®®¦€°þ.0½xñâ¢E‹tnܸÀÇÇÇ„Y^F[¶l ::ºœs =J·oY³†€¤#* ˜“˜˜Êåðô믫lýÁÿþWóå—5Na8”D÷ä´#æ¤Q»’’Ú…ùûÕ9r9íÜIÓ¦åä Q/G¿RSSKQ*•ž>}jŠŒˆ .£jµZ$((((÷‚¤¤¤Çý1Qœ;GÀ}'77·’°÷fÌ €Ú¶%Uµ6*•ê;ˆÇ#“—0ŠÐµLm_Æ2uj*mÍ¥{rbeTuÃéÓdnNýú%$PHåç›:'ý3f €íÛ·›*Ëhjj*‡Š.¸ïïçá!)*o“JŽ xZiq(ÉåÔ²%O>ÿ¼ÊT*P(JÏŸ¯Ù`•ޤv,)©˜¤Öiiôð!ÑG@õ} ,$$ÀøñãM•€§˜*ZM_„GJŠG|¼ºhé«™™ [7.Ð<%¥²¸Báã7Þ üâ eUƶ\._~y³uk¾B!4ˆ“¾Ppu\¨ïx0ËTÓàì Ùo‡èØÓ§À{ïaÂDG›6µÚ0`ÀgΜQ›ÊµÅ°ª|ôèQC† ©ðŠ¿ÿ¦‹u=¿T|@@Ìĉ•GVH¥„B JÙ˜VÀ“¨¨ë66¯/+&­Y¦v/Ï2UãïÇ,SDAÙØ‡£í¥Þ»WÏ6…öôôpËDKõêÊd²RG*©vÒÓ±cŒ›[vaañ‘6m$8Pù_™Y³Ÿ`¾n]uvZháãã‹öí‘Xï =Mùm‰ÕޏÒ—š`ƒ&ZÁƒü’þ~o¦âë„É `½TÃanŽ;wðí·ðõE|<ºtA§NÐù5}Ñyíµ×œ©´,Òxè%£?ÿüsppp¡Î7[³´MüäQß¾›6q>@ Îή¼9Á„ ŠŽ‘œ|åÍ7«“×Î.ÿ·ß’y<×èè„~ý˜Mc=¢HRêg™*c’ª7-[bÎxúîîèТ£±nrrL\U˜¸zTŸ®lJJ ŸÏïÑ£ÇCÍ“ÑäÉ“QfÊìÚµkW5{‡%ΛG@Z)- (QU×>ûŒ€,.·03³šIþøc)ŸOWóÆ Kª’ŽçÓ§™•ùû‰Ùü”Þ(•ÚÚÒwÞ!€æÏ7uBU‘ÍãñÌÌÌ*ª2*úŽ2€H$Z±b…\.ïׯ€“'OQllìŠ+¼½½7n\´â•ââèâEŠÕ ¢˜0€Ûšª¶ªˆÕh®Æp±z¨Oœ >Ÿ€Äe˪ã'½RIÕøûå2IÕ³giØ0zü˜ˆèí·iæLJJ2uNеkW§Nªû¦õ•Ñ_ýµ¨cÛ¶mÛfÍšX»vmÿþý¹\íˆÁ‘#GŠ®—ÉdÏž={VÒÏëéÒ¥·±©V“aa¨,,²£¢ªŸç?óç ${öTÿ.F}¡:–©ÙLRõ %…„B‰´ÎBqq¦N¨ }ô€Å‹×}ÓúʨT*µ«ÀéNØ1ct¯O>þióæÑºááäØÙ©«7;ø´MÎWåWR¢ …bŸ—dnNÏG/%Ì2ÕHDGk—mÿóñx4i’©*Éßÿ  cÇŽuß´ žfÍšU‘†ÚÛÛû9QÞ½{8;—¡R‘­-_#öïW…|~þ&ª”Jš<™€++ÅóÁ\ÆËD],©žøû%)Me}ãçŸÉÜœ, " §“'MÉår+++‡SvÁ¨±1€Œ^¹r¥"ݱcGé« ºx‘ÊX¼ú*×.¬f£ò‘#  Y³j–«BqßÍ€TíÆµŒ³L5 ))Ú_ ¡C  -[L <À¾}ûê¸]¬bêÞ½»¯fIDI†>mÚ´ÒG‚$OÏ(•J¥RéŽmÒ@ÂÕlTøÕWÄã©~ø!îܹä*ðŽydaÑ(/£G£LÝ+ã%Æ‚ƒ 3|`‡½.¸çƒ®Z?qJü"Á‡螈WñA~‘ ùûUŒ‹ œA„îÝѼ9&L€ `Z¿:“•=DŒW¯^]*¬µµulÉéø""ºtIsvÎ.YÞ”¹?-[V¿Ñ‹ÞÞ\­É-TqqäáA@l·nUz0^z¤:.Ô>%{©Ì߯:h¶,½p²³£J]†ŒË½{÷¸»»×q»†‘ÑÄÄD§+£›6mªèâ¬Ö­ È=q¢ÄѼ<âñH ¨¾ÛLüåË…<^•{Þ•ŸÃÅ‹9±¦³3`¼€TÓ2µ^­“¬#òóéë¯éÛo‰ˆNŸ¦®]鯿ê:µZíææ 22².Û5ØšzMŨ¥²âqûÛ·éþ}*S%›ïãCÀÅjx83>y}úÔ"á_fÌ(Ôls_±â32…:–©~Ì2µ&hܨ׭#ªs‹èI“&ØR·ƒµ“ѽ{÷j4ÔÌÌ,""¢’+ÓÓÓ###3Ë,Cºß«û5{qU“´4©@@Àƒ~¨EÎêíÛ Ps8)Û¶ÕâvFÃA×…º=ó÷« ‰„6o¦ü|R«Éߟz÷¦ Fø ÏÎ;Œ¨Ô ÞàLF%‰••€*Øw¾ˆ—,Irs‹Ñ”Kè²a9AA5j÷ï=H®í÷F"@ÊáÈþþ»v ]ê%%µMMLa’ZLTÙÚ’››VR+í_†ÄÄD‡cmm­PÔÝx¶!ò¦L™Òºuk©TZùeÉË–>aBéOŸ@öö5šöÉ‹SÙÙ@§O×4a"*ÈÏÿÓÍrr¢r7>a0*%¶öŠéýtê_Ž¿ßÖ\º!kÐþ~tù2Ñ¡CÄåҽŶmÛ¸¬iµN0¤móÔ©Søá33³Ê/s7W¯:mÞ\úDóæÈξ¶sgõµñðà.Y vâDª¹‡“¹…Å€§O1`22rºwW%'×4£Ó”‰VøÚ ×ÜK¸PküýÖdcLJƒö÷stÄ+¯@t4xÌ@Šªª›ëœF< µÀjGœiŒ›îØêŒ©Öh'„ ¸¯À¶.ãÇ>œ¯¿ÆáõŽÓ0Y“JTë² j ³ážÝŠЉéÂÃKík)áϪwí2%Î< µÀg8î†[îØÑslÐN5p_ŸÄ˜›ŽNñx- Ë2Z€œ—NRû÷Ç?ÿ`ôhH¥x÷]ôí‹™dT¶N×›æÉ¡pÜ8~ýÄ×®•=e7t(€665É„«WhúóÏÕÙó®"&üñ>û jµr„Œ£Gk§¡qSŽÓÒÊ.«ÀRç'NMpáa¬Ú Kl¦3$W6esäá5sÛã¸Âu$•€G…øERZR³^IårÁá€3f woôî ©‹!5µö1ìíí£¢¢âãã —i…˜`l@¦¿¿ã­[yØŒ[úÜñã>¯¾Š‹k—¸uëÆ˜1]ûMŸ ôìéwéR.Ÿouï¯<ÿ*F¤øQŒë2HKþ(ñ€'ÍŠß^—a\ªvNIìc¸œJ81à“,ìªÆL/sìjTáÙos±öùlsll_Ýòb’¯Æ…v,õ®JorS¾v,µ»_˜ù4ýY³Ë–¡W/œ?_û £F:räÈ?þ8uêTƒeV¦é:î߈›!CÊ9×½;ò°°äØØÇåp¢Þz €×¡CÙµ¸]#GnØÛÛ*•¼aÖ¦O¨—Ú a¡ó£4Ö ïÙb^É9ÒnfXd‡åY˜ŸµÙ\FC Åm‘ÙŽFC¨c,¹2C°=¹âžöºà}[™AP¿_bý÷÷<C†àóÏ`×.Ônº·.‡GMÔÍÌLNNvrrruu-{6ÞÊÊ#?ÿâÚµ=/®EðWWßÔTåGñW®Ô'Iun.·Oܹ“Ú´i£ÿåXYU}O¦¢Ÿ?AÿîŠNµÒ¯ªÖVÉBTXmú·SÓ´ÓßÍø8Û‚—´Š¨€p[Ž›2„ËqC^¢ª¿)þ"˜áU3xÔç^jz:||“ƒ°0ôèQ³{=zäãããä䔚šÊ5rý¢iz£éë×7éÙSZJZ  '¯–}ßC‡ð7m’ë7,µµ¥ãÇSD"—¸¸ÇP½x“¾/8p«þ*«¡Yjì—`F:¦=×P'Bœ_Z EU.Ô‡ó±,A‰HÀÜtü")þ#W°·ÇÊ•xóMôèÜ\,Z„ŒŒêÞëííÝ¢E‹ŒŒ ©Q1ŒÚY[ÛggÛåæ–{Ö~È….Ô2z¹=z@"¹üŸÿÔ:C œÆã¾ûNÌç{EFbÞ<=£1ŒG´K2qªjÀŽ‹)Ö8å_aÕ7¾˜s ÂìuÁæ8î†`{ô3‡i*„`Y&ú'i%õG1î+P/–¤òùx÷]ìÙ+WbýzÔhœSãÞYÏõ¦y¨Gv6RSáîŽòž” ïß´oŸÆáØJ¥¢Z-nx|äH‹Q£ 9ΣGBÍ"^=Pÿý7wð`ÈåѳgûlÛ¦g´—ƒ<Ôç«QP‡zlKvÄjøÅÀ·Îlã ºÖ?”@„a2Ü”á¦y:“ûN¿ÜMœ@”#Ú)•‘'N´<¸vM¤ôêåzñ"fÍÂwßé•+ aݺ&‹ºy³[mWI½Üè)£i*ŒNA Hª¾¸Ü™ú DÄ+qß6/ûúŸÚ¡*´ËüÃd%ªúyè(D€‚ÌÐVh¢GÔjóä üü —#">>•]™™™Ù¨Q#¡P˜••en®Ç¢ãª0ÍwLïÒ¯Ÿók¯•šÃõê uff­›pýáðùêíÛŸâ‘û¢E¡\ÀmÉÔ•ßAƒâϨ ×¢ò¶BØq™†Vh'Ä4kluÆœnŒÕŽj{.2U8+Åšl K†_<ÞLŶ<Ü”—(®zqpsÃÂ…xë-øø %6 ì: ŽŽŽ;v”Éd•ì^lêÌ’Oyn.j>ŸÔ1~ù%y“&éÓÊÝ.]8o ý­T*½û.RKËÜ7 óeâµÄb«Í۲߾*‹6æè•€Šˆm8_;4–©sÒ¨c\=³L<™š1£Â –.] `éÒ¥FMÃ4»…66¸w“NùÝ4ooñ5_ªK“ï¿Wp8=q÷®>q4p¹\lÚíëk–Ÿ_Ы¥¤è“QD¶oèQQ–¤Äx3ä.§ƒÆ2UÓK­_–©ãÆ¡C,]Záu³*ÔDSL@LLL^^^›6mʵy¦‚‚BKK>ûô©}óæµofÁlÞLÇs ´¬3#..¥M¿ü|øûãüyXZV}OÃ`p2>¶Úï‚À Ì»+ò —Ã_Rùaɸ¯p¤¶\ŒRY¦^•¨ê¯G–©2™ÌÑÑQ&“¥¤¤8;;©“$©§LñîÝ;ïäÉrÏr,,x]ºpûGôjæã•ææœcÇn–5Û¯NM›¶‰ŽFóæ „²þ/1MuʼÏ?_\_jÙ·ŒðV¬¸X`‹á–ø[Š›ÏW飡ù¤ÕP\–Õ>C—¦|Œ¶ÄjG\i‚îØêŒ‰VðàCJ—c[ÞLE›8 KÆšlœ‘Bòâ-ó733 R«Õç byR†ôôôÎ;›LFxÎH±5PMùèn†96Å–ñJôLÄwÎh+åÛr,ÉDš oXaY=÷"©_¤«pãùšÔ:Uý< P»&5Ȭto]r÷îÝN:5mÚ4V?Ÿr ¼~ýºÉd4---..®Q£FM›6-÷‚‚˜ oo)Ÿ/*(à z5¶z5þûßÌ-좣y|ƒ­1¦ýû9'‚(fùr¯Ï>3TØ—•_%Xš‰pw8³âø—” ®W ©-Ú±ÔWÌ´¾Úu¹ºº¦¥¥EEEùT^hZsÜÜÜL6S wëÖV}ûª?ü°¢ ,¼¼Ð¼¹¹RÉ-³eS™??K(t|úôüèJÎøñq³gƒ¨éŠ5Ü<ªb ¿QÆ …S.Ôº–©ãñjbZ¦r8ͪÐ35ÝS£*T*UZZÚìÙ³M&£¶..Öb±C¥ìÔ½;€¸}ûômÌÒòñøñGÍ7a®÷-[þòöNsæÔxÿ¨†Æ\ùº TÀObd1³——]êØë‚96ðÿÜßOãB­‘ÔCùH2æd­‘†GÓÓÓ…BáܹsM76*•"#ööå.«×psÊ”€;Ï7iÒ;!AÏÖH.ç´iƒ'O°{7&MÒ3š.êÂBî¸qøý÷<Ax¸y™]£ElÉÅ :‰àÆÃT¸²§û†G>áÎóýþQ °<¿^f%æ õ'!!ÁÃÃÃÖÖ6##ƒ_ía½ÜÜܰ°0—üüü¬¬¬ 6´iÓ¦è‚û÷ïoÙ²åûï¿7™ŒÊåòÈÈHµZÝ©S§Š®I8~Ü}øð,[[‡œœŠ®©>ê;¸ï¼“$Ú¥¦ZØÙé°©4ÖÓ³Yrò{û–qq•üa`0ETb™Úˆ§K 2+QKW~ÃG€ ’•Ë­[·ŽŠŠºråJ÷îÝ«äèÑ£3gΜ2eÊŠ+D"‘fÓf''§ØØX^YO£®‘ªqbb¶]®½}e)•dcC%&êߢº°ð©¹9aú­1-—Äþ‰‰ !C¨°ÐàñŒ—›5ÝÑÖ\š˜BÞ±%Ö¤úÇÓœ4Ú+¦(EÕqnȨù3jKûÄ%ŽÏ›7ÀŠ+ª“̶mÛ¸\îâÅ‹‹ŽyD%''—½Þd2ª,,Tñù¬²Øòž= xüÕWi4fõjÈÍòó PUT9;Ù³§Áƒ3 ‡B5Ý“k%Õ§¤¤v‰§9i´#îÉ©ÜUþj¢­¹Ôü5}FÁTÔ£ùý÷ßUÙzhh(—Ë T*‹M²³³gÏž½}ûöro1ÝØ(€ÄD89¡RGÑ«v?uêLûö¯•»¯}M!‚¿?nß~[Ïëb=vì''"lØ`€¥xuóf|õˆÔS§>ݾÝM0 “Š,SíʳL½&Ç*G´"²#Sð¢ZnOû÷ïÇs_¨êcJµ³±šçåUv‘ÌÓ……~ýÕPí6ß³@£Ý»´s2gñâØÿü‡«R9Ïš•sé’1š`08<ÀG õ÷»åŽÃ®Xb‡Þæ°ä _­õ÷›•†ñ¦Â„ؘ€JeT.—kö¿óóó«Q2¦”Q§;‘›k³`Aå—Ý67ûË/†j×jà@å€HÎh¨˜¥h¼ÿWW+µÚnâDè]ôÊ`0*ÏAÞµÅÎFxØ´Ø2Õ‡,ÒT°á¢€°É±µó¬Eñìœö¼_USK=SÊhŠRy="âÙ³g•_f;h€NRiå—Õˆ´>P=îÞ»|Ù€a‹ˆD11èÞ iÝ»+²²ŒÑ ƒÁ(‹#Íùh)@+¡ÖÍV³—Ÿ 0_²Újüô³gÏ–{£……Ö5'£Ì>ÎYYY ÷‡L)£’={Úõí˯jËÔ¶3gpŒŠ‚አÓ±£ÐÔhA\KK=šjcÓ(!!ºcGæLÊ`•¨B|’…!Éh‡7R±.票aË!ßœdï ðçMhg'Ù¿c[ûû:::¶jÕ ÀÑ’.ïIII³gÏ.×`^K +º IÆž=ˆ»w¯òJ©½=q§O²ù¨(âóI xvæŒ!ÖäÑÉ“™šòØéÓ× ƒÁ¸*ÕÖ–zÆÒëIê÷'ÿ| häh‘Ž?œfù‘HJJ*7ÈÁƒ9€… FGG?~üxË–- ˆ‹‹«¤iSÊ(I¥””D*U•Þðð àÂäɆm?qÐ θº6l)TW¯’…wÇŽ5jC FC&=¿`îí'omý©S¯>º çEÀkÀà—›liÉx\®ªbÙ ²°°°¶¶îܹó† d•."Óʨ\.¿víZXXX•WF¼óÙcÆ6œ{÷d€šÃ)¸zÕ°‘K‘·w¯P¼C!ƒÑ Éd§OŸ^ºti—.]t¥S¼| œÒ8œË-Z¤q¹'¼¼4oÞܰi˜RF¥bq™™ŠÇ«p›å"®^%€|} žƒxÚ4hăG.Åß#F@>š¥ú IDAT:eì¶Œ—¹\®‘Î=zM às¹þBáRç4  8åĉ ¢[µ" ÎÕuK»v¨Þ’ÐaÒ‡z"…µ5êôôª®S j óÑ#g–¦¶²"àš5Ž\õüù(ÌÍãŽ7v[ ÆË„B¡¸téÒš5k^{í5Kíx¹\n7·¥žž§…B1@€šÇ£aâFÊÝ´‰ˆ"-JmÔè×ñã3š7'`%— `„ †MÏÄ2J99Õ%¢{¶¶\û䃧pkÐ Â--ÕUvŠõD¥ŠïÖ€>??2Ò¸m1õ•J®‘N+óI‡Ó¥K—%ãÆíÓç©fþ ÖÃãô°a™÷^% ÀÂâî¦M9ÎŽ³FŽ$''>‰DbmMÀñwÞ1|ð²<~œ-p³}ûºhŽÁ0r¹|âĉµ¸÷ñãÇ!!!cÇŽuuuÕ•ÎfÍši¤311Q–¸d õè¡æp´je%7îê_(4]‰„V­’,_ND9§NýӡÞ/¾x´aƒL#µS¦Z­úänZZJ$’®]»¸råŠa¿¦-( j÷ÈžDìÚeŒDî͘A@²£c5ÇjõäáÎ\.T=;nãE#33³W¯^æÍ›WÍ[ž={¦‘N777]éôðð˜9sæÎ;?~LD”ŸO;wôë'{Þ÷$ ÜÍíâ{ï©K®«®\!G!dDEQ||¼úàA ¸Ü·/©32´;h\ºDD7Py-}-0±Œ¦¦¦†……Eß¹S‹ãúõ#@¹n12QËd h÷ncÄ/§Å£G‰Ç#'¼Ú?… Æ BLLŒfÝ$€Ý•þÊÄÅÅ…„„¼õÖ[-[¶Ô•N''§±cdž„„h¥“ˆ”Jõ„·i“«éajàkë¬5k(3³DÐ?þ(ôóËyøˆ½oÆŒ¨¨("º0mšŠÃ!@ýü7âõ× ÈìÜ™ˆ —Ëåñx…†ÞæÇÄ2údË%—›T͇‚ï¿'€Œ·èÇ È´±ÉIK3V%ÉZ½šµeKÝ´È`èϹsçtç„cbbJ]žž~àÀ™3g–’N‡ÒÒIDDñûö]ëÖ­ÐÅ¥hè3«Y3Ú¸1?"¢tÛJ%åöíKÀÑ#‰H"‘QæÚµ*€€§sæh/NI‘òxjà·%Kˆ(..@ãÆ þ 1±Œf=J€$0°:g\¼H@š@`¬l”Ê8++~4ÈXM”á|—.µ5U¯KÎ`˜–}ûö‰t6þqttÔLòdff–+vvvé|ðàîîFD”zåJÎûïS›6EêIÍ›'Θqð`9 ?z¤6,sÜ8"‡‡ÿ5bıC‡ŠÖtþïÄá¨9œÓ£Fßòá‡ãœÏQ~mT.“•p8PÉ9I›7#€ÂÚš‰šwu¢Éȉ@dj*WO§m´Ñ‚X¼xñ[¡>ÞÞÞ .twwçr_ÉÅ3&00ðñãÇo¹NDÄü|ܾ½ÐѱÆ{ÊLLnxzÆ8P÷΄XŒˆŠ˜‚ËëéåÆÅ!bÕk[Í×ÞËŃk*22mmäpð¥»8uê|øá‡4¿/w£2™ìÎ;wCB”¼¾¤_?Àcǘ2ˆ$ÑÛª6l`ª‹ÚˆÅy;"@ŠžžL]ë m´¡2™ìÿþïÿê œÐÒÒêÓ§Ï×_}õêÕÊÊÊ:š¨¨(øõ×gÖÖÄËmwÀƒNðüùÊ“?ü 01É¿c¾þúÔÎàõ ¤K—"€àÉ›‚±C‡"ÀƒöíkŽlÛ¶ ¾üòËf¾µÑ°U(Uúú@Öù¾×æÇ@Q³öÁä¥KPÌád¼xÁ\/o!LKK×ÕE4¨áŠÓm´¡~JKK‡ µcìù|þ‚ .^¼( ë¼—HžoÚôÂÍ õô(ï)`P('§Þ.¥R,,DÄüqãH€ðéÓñ-Y&‚ æÎER[;âûï߸=-ÐÒ".¾V›}ùòåÈ@Ú·¦'õˆbkkB[[‘šªÌÅI"@¢¡!£&ÅÚØ Àó×Y˜G66ïíMÖ|\òóqÖ,6L–´ÑÆëddd¸»»70uss+))yû6’L$•¢r8XÊlm0 AkÖ¬éÚµ+ÇkÀ“4èU"SB®^] ¯ÿjÛÝÂâö Aÿý×x±±ˆ(OI‘kiZZ¦Ö7#”ËqæL¨x\+R+çpHxs£ßÏÏnß¾­ò»Ðšw£/^¼¸uõjq^ž’×Wyx 2)Yˆ8j<4ˆÙ^j¹aƒ‚Z9Ú»·úЈ€ zôè_|áÝ­›ÖË=ú ŠÇÃY³$/2™Rm¥¦b|<"fÏœ)ÒÓ»Þð·XѾ=%àT·ƒŽ‹CÐÒzpüøë‡I’ÔÖÖæp8uºæf¢y7Z´`¡­]±q£’×G¬XO®üˆ1žž ¦»r‰2ü1Tp8©§Ocd$`‡ê7£6êCZQ‘öË/8f ¡­]pào¼ÍÞ)Sĵ×Ië‡8{–ÔÖÎóò"IRVRr18ø­ø7¨ªÂ‘# ˜ÇK=s¦ÎKŠ©Ù[-q @–––ÊÛ¦<šw£ª’pó&ˆ´´°v<Í=U×¼“DG3ÛQmHòa§N€íÛcJ š™!¾™øÑF€$14T2eJiV‡oi6gŽ\¥‘ˆ &IR–—'Ö×ÞµkJllÃw”ffÆZ[#ÚÙIŸ=«óšÊ°0@ÊáÔ¨>~üºu릂‘J£y7š——w#$ä¹Òš+$Iöö€ÏŸ3j"ЦMC€KKÆ),ÀÉ“ñÆ $IiE‚%íÛˆGèÝ;÷5™ä4]ÝÂ+0#Cå¦BÚ±#¤<ˆˆIá቉‰ÜRV–`e…}}¬?ª§Üßμ+ZÃÙ³g`ôèÑ*[«šw£é‡!€ÀÓS…{¦MC€R%äõš‰(.NÊáigÏ2ÝŠDhhXýíÜ·nŤ¤"++Ȧ–í§Ne܆6Úx“¬;wî "qu­ñž"\½º*"¢)Í…„(<@ÄìE‹rÛ·¿¨\1 "?ŸJŠÉÑ×Ïi údx8r8¨¯/¨+ j÷îÝðÉ'Ÿ4ÅìÆÐ¼-»s¹Üªž=•¿%tÜ8ˆpwgΪr'OF?^ }¡@€èâRý‘åñ¤¾¾/ÕnP]"~m´QœPôÝwo}MœXo¾¦H@“¡Pbñ£¨T÷†Ið I[ÐÓŒçIóôD⫯ê<ûÍ7ßÀf²5ïF›Àý{ ÈÔT ‘DìÜ©ŽîQ.ÇÓ§qøp¬q zzÕ¯Ÿ>U“ m¼›TVbPPnÏž5BŸ„®n˜«kôO?5=¹.9Yºl¡PööWÇŒÉJOWöÞ¬¬"KKH20 ØzB^»†B€GµCñqöìÙpäÈUÍWÍ»Q…BqûöíëÿüÓx™åš[¤Òêù¯ÒѦÍ!õ£ \Ov™ÂFHNÆU«Ðʪf>õ€9‘À6Þeäòâ?þ¸ëì\ùréSik‹AAØÌ<¹\jcƒI?ÿŒˆ999õåŒÖ¦ðÑ#trB€¬p£Mãú¬YPà뫾.Š| 89x°ú:­‹´´´Î;߸qC³f´Á.âãåË—góx5KŸy&&?üP’@sGb±bÕ*‘£cUI ’ä“É“/ÿùgÝ…C”#uÛ6)¥L:{¶òøï¿P¨£“ܘêźuëà;å’¦š+Üh^^^è¹sϯ]Sí¶¤$@KKÞ÷f“¾e T«­æ]}P³û¼¼¼C‡iÖ’64Lnîí‘#«S}(¡O>?Þ33³™mžûðÃê w*–HÊÙ¶ „¦¦Ê¤WÀÆöQXáF+ž=#øü*ooUo¼mf†±oVdœË— LK+îÑ#ut‚£F¡¥eud¤I¯ŸRùæ?ÿD±­mžrÃa333hB«’°Â’$yýôé}û”Ý¡«áÞ=@f쪗‚3gðõšwÏž!zyÑÜMtô+u’O?ED6mÚ«V­jb§JÀ7š8u*d5¨/P'e‰‰ åóQ=v§N¡©) £#Þ»GÌ‹÷Úµ£&_´õ²i¾VýæÕžššÑ§¥¥ý¥ÑÜÿ6@"ßþñǧbûöÔ–@__ÅÞ½ÒÜ\5SùÕW<|8"Væä$ÄÇÓÞ…¨¬,¾[7@cãÜ“'›ÜNÞêÕðœÇ+Ve/dÑ¢E°C‰(ý&£ìÀÜËK~ýº¹™™ª7ê;9¥p8®ryŽ{Fƒ1`Ú›Lž ½{ÃŒƒÁ¢E2§Ÿ@ —ÓÖ‹™L›‡A~~õ‘Ù³ÁÁLL½UGG§¬¬Ì××7??ßÊÊjĈ´YÕFó I2öÜ9ÏGxÁÁ³³«véò¼gO×5k ÜÝy<µY/¹zU÷«¯`ölaPPª‰‰Db`kÛ™öŽ$’˜.]zåç‹tu nÜhïãÓÄv**Ú9•+Wš[X(_vv6ØÛÛ7±_e`ÎC«„¾}@¶u«úº”ËqÝ:äñ Êܼz¨hhHs/Ô\•I} mPl!/ؼùõ|Í2}ýÇþþ"Õ÷TéA ´µ /?, S“’”©.תª0 J´´ò®\iNK¹_}…اª7öìÙ]éb‹ÍÏɹñ×_‘Ç7åæýûk¤žŽÁ~ýðèQÍ«›+WÐÆ©’s¤ŽÍí7Ã’$I}1Nž<™@»2EJ"Þœ6-RO¯F賂ËŒwïj¦ÈkY™tÕª²Ç1{̘¨^½^„†2×[AJÊ jakK4³zGyy™–DmÞ¬ê­666£J"Ua‹;v ÊÚ·Wáž—a=Ù!!Pl`P}|Æ Àݻ鶱.êa‹ €*z·šáF)NŸ>Íáp:vìHWö^Ê Èʺ³»vEòøqLIA´°P§z"^»†;7½–w4ÛâË{‰D²uëVFÈï4OžäM™’E)QZffÑ 0ž¯©dV–œÏ'².\@D5ÌKnÝJ¤dS<I¯8²u«B$B’Ä.]xø$~ôQuÐ{AnØ€¸x1:„HåhÒNƒbKò’’ûöíܹ“¶îèp£“&M€¥K—ÒeZ+gß>TBÆBsÞÛ;ùeÈ'äèéɾý–¡OU ¯òóË¿|S¿øâÆÌ™©IIêè7+«ÄÚR IZ¢÷óóE\.ü»r¥׿;88œ9s¦æÈñãÇ`Ò›_UÚѨ ÑÞðÐ!D,hß*ïÞÅ›7«3^†¯ª¢ªY¡Ÿß‹_E€Lkkœ=‰ilcbK÷ïßCCCÚ„dès£]ºty¡¢dÁ; UL»Gú"‘_ܺu~èPEß¾5Â12SS\¼¸ŠM…¯ þïÿ ­{w’$ -šL’|õ*Ù¡ººVѵ¥³r%Ä99)K0nÜ8˜I/ÚÙ9kÛ6uæk6‚XŒˆDAD_Ÿäp’ÎÃæ×öP‰gÏdææðÌÚZZRBW«±Ã‡#@|—.Êß"‘HÌÍÍkââ­¬¬ {÷îZZÕ©F\.÷Î;tYHÁ7šžŽÈá¤ìÞ²gOé’%€£F©ÐÂÞ½HiRáÍ#GÒo¤ÒbK×®]³µµ¥G¤¶=yíí±_?\±;uB}}œ2E¥¡ÐêÕ«§L™Ò&Uûö!‡ƒ\.þñu ñÈ‘³ŽŽ¥ø2_3ÃÁû Õ¯ÊØ ò£G%––™üˆ)[·Þر£”Q!çZDìÙC˜˜ €pð`y3 Û½Mf¦BK‹¸øÓO*ÝGeÖÇ¢E‹h³ð%,p£ˆ¸q#HML@nlŒøï¿ªµ@9_ê‡>}ÙW(-¶”””Äçó $ofŽt4:9½êtëVLKC’Ä3ÐÇ©ÑîÙ³@E})‰B¡  ûçŸèÕïiÙüõr¹Èá(¸qà@ذaèîþêÍïܙؼ™þúšÍ§¤s-B€Ø>}Ô:ü|ÉÓ}ûÊ@2z4Ò› õé§P5z´ª×Çëó¡LDË²ÃŠÅØ±#Ô“ßÆUk“É ==«?ô÷ïÓo¡*bK±Í¥Týkÿ=Š3fàëʉ|¾2•ßâ?þàp8ÞÞÞL¥¶,ާòzqÂùë3€víâÆìÄ IDAT²s$=]Ô³g‘«+¡PW®ÌÊÈЀׯ£<õòR¹tEƒHbc\.Éå6-¼k×®µ}(‡Ãa¨&9;Ü("Þ¾5awß~Û„DR;;Ô×§ù‘Ø$±¥ÊÊÊM›6EѾӅø¶ÕÑÁÿýOÕ6ÊËË{öìùÇËÙë;ÍùóTu_ÙËÿ¬ŒÇ‹õô¬ ¦9 ˜.$åå•ÆÆ•úú±ŒU»l”Ë_}%×ÖFÅœ9´o²E÷郗ÌÌšvûÏ?ÿ\ÛΚ5‹^#k`E”ŒÈá`bb›ˆWLœ(¢·‚üÞ½¸fMuî<õ3{6®Yƒ¿üÒÀMk×®€aÆÑi n_nÜ‹ÅâÇÓdY ãÈ‘#ó\\::”ë$„:à’%ŠlÙ|“ÊeËH/%03Nœxrë–¦R*Òÿ÷?JaºhÆ úS]âã‘Ç#¸Ü›M¨Ô„ˆˆ999<ÞjY666EŒ-j³ÈæEFJ´µsTÙ•{‹µkךñù{öì¡ÑªjTÜ4/..7nÜ}&–hr£Ç€ŸT\Âo¹íÝ»÷Ò¥Kˆ¸}éÒJè³Î>]]qèP\³FÓV#–—+ž>EÄÜï¿'¸ÜGcÆ0WMÈ  jäñÀL¤ J'OFlÞ>-õÙ®áØ±ct™W¹Q±Xœ½zuA3$EöîÝËårW3Q¶¾©±Gôï™ÒêFoß¾íéé™’’Ò|»ØŒH$¢RŽ9þþþˆ˜žž~üøqQq1ÆÇãµkxè~÷Ξ¢³35ÓGdbJ¡ ò¨(©±q‰••L$"e²gÿüCcu¹&ð÷¨QµþÆL ÅÊ9—[Ùœ.óê„EnQ.o΂Tyy9S¡Mr£;vì011¹Ôä²3µ Eww´·G*ä{ófäñpØ0lƦ5»‰‰¹ÕXÕ¼Jtt´¡¡açα´´tÈ!”™**˜•…÷*²¤üüy¹DBÊdeÖÖŽŽÉ,È’nÚDß“,`¨‹‚Aƒà¬JbouQYYihhi ˆÑ»Üè¥K—Ž=Ų́Ƅ„ú力êF`ñâÅ4C7III&&&FFFÑlH§™LöùçŸwêÔI"‘( ›O¥þþõé!°òÑ£ iõjDDEåÑ¡ñÑ‚(^³9äpžª^ìGYž|H³%̰hÑ¢ùóç77ÖUÓÄÄĬY³†Š‡õööj*Pñý÷Ø { Ÿ=+?u »w—ßûòKM[„ˆ(“Éþöð¨Nriê¶2dRÚ4<þûï¿þýû«!œ–]n4...>>¾‘Ñhƒ2Kk×®µ´´¤÷¹y™………?üðÓ ÍD&“QŸ¶àà`5çÀ4ŸÌÌÌÜÜ\|)K±k×.D ½{÷.I’è! P}jÌý/‘þ÷Éå MLDÅÅH’YêÑdRÅŠ ˆaríìêUÄÑ´¾DD<újÃ.7Ú8É,1OÞ 7êããJ­Çišÿýï0pà@äÃ4mÛ¶q¹\ª|îéÓ§§OŸ~ïÞ½7®hXaÁ‚êS+V¨ÙòWW®^-.)A‚(tu}âç—[§¯&J$é£GS¡ ) GtÈýýàßNí… ØåF###ƒƒƒë}€('³TVVvãÆ šGÍp£Ç÷÷÷¬´D),,ìÚµë™ZâFl#66vüøñsæÌAÄ»wïòùü ìx4¬‡@ „CµZ£F(óöF€¤ù󱬸˜=B.éÐ|>^¼Èl_·n!±M²@ØåFoÞ¼¹nݺ۷o×}Z9™%www yQ²>7:w.vFáС8l¾5zÍÆ©( µ¢RQQ¤i[Þ@¡P„„„lܸÓÓÓ9Ž‘‘‘X,&I²׆õ.\¨>ÕàÿŽ~B²w¯`ÃD,:z4ÝÙ9ü·ßÔj@£Èå8}:Tr8éÌ'¼%u耂ùó™îˆ ØåF ãããëÝbRNfiáÂ…>>>õúâ¦QŸíßÿ•¸ï÷ߣ¾>Öµž%•J/^lkkËl1š ¢OŸ>°ÿ~MÛ‚ˆN’dee¥‡ÃÉÌÌDÄ#GŽ(ÅÒ°Bbbõ)õ‚ÄW® €XO¯<#i.†ØlŠ‚ÈŽ+›WYdW¯"@ @´šf4Á.7ÚJË,ÑL}bKˆxõê«ËbcëÉ¡0`‡Ã9qâ„Z,n..\ðööf´&­’ 4ÂÂÂqÉ’%«V­¢v“”B=¹ù|´´dÀö: îÝ+yÿ}aF"¦öÙg¥¬vWbq¸µ5Têè`ó Ò)Cÿþ=eŠ:úbv¹Ñ‚‚‚ãLJ„„Ô}Z9™%’$£££ÿýwzlj@lé-ž=C_Àü8 þú ÐÊ i÷V¬s£ëÖ­Û];T™%’$)ùë 5K‡ýñòù ‹ö§¦¦«Í¢f¥¯¯oiiÉt"ŠÅâ£Gž>}_¦-Lž<KKK›}Awºùå¬ïÉ]PP>o^µƒ5|x‚z†xª“úôi$%VikÛœÔ8 ÉtKK¸®é¤ÛæÀ.7*“ÉbbbÒÓÓß>¡¢ÌÒÇþë/–ÎâQ˜’‚=z @¡‰IÉ“'jê• °kW ~ýUM=2ëÜè¹sç:TYgE¥¿R©ôúõë¿©'‚D.Çùóñû¶fX§)™È¦ñÝwßÀøñã›ßI’7nôöö …$Iº¸¸¼÷Þ{Ì.¿0íFçÏGôòz¥ª##b^¿~ýÑGô÷H7‘.$Rúÿ¨ü^³Éܶ Ä––Øb€untïÞ½ëÖ­«{7VéïƒP(äñx|>ŸöÔÛTTà‡¢*ûïÙÙÙÓ§OŸÒ¢6%³³³ÝÝÝCCCkŸ’J¥™™™qqq +!‚;vPÃðµFœŸŸÏͯ`ÔRÂuu1:eåîîiˆX±re)}e2™"3³¼];H52"ÔèC‘ rÍÌàøû﫯SfÐj „žF9r$‡Ã±°°hN#FFF3fÌh×®D"Ñ×ק˶·).†áÃaìX01êƒÖÖàíÝÀMçßÿ%"''ÇÎÎŽ)ÛhÅÎÎ.**JGG§¤¤äêÕ«}ôH$’°°°òòòšË¸\nÇŽ===kŽTTTTUUÙØØ,_¾<88X$}óÍ76l IràÀ`mm­þ?‡6øì3€I.€ŒÃ1Їœœâ¬,‹=|zôд‰}ö¬ÇW_ e;Ûþ÷·];õõ}âDûÒÒrss¿  õuÊ ¬s£NNN´´¤†ÿM\DEATÔG†‹¸ÉÖÖöÈ‘#½zõj)>”BGGG&“ùùùÅÇÇs¹ÜÉ“'‡††Êåòׯ!I211Q.—÷èÑŽ=ºpá¹sçîÝ»wΜ9R©”Šê§hkà“O °† ) 7úúëü[·lÞ?mËþ¨Qöš6®q9Ì›ÇA$ûö5 õõ­PˆW¯Ö0ùùgggõõË \Mð6Ïž= zþüy3Û)**Úµkׯ¿þJ‹Uuãçˆoÿ4èC)¦M›æêêúäÉ“¨·\0»ÑÖÖ^¹reÿþýýýý###ßò¡5¤¤¤|üñÇàåå%“ÉJKK`ذaÿý÷!CÔj1£:çσ©)üù§¨²sNçeËìß{OÓÆ)Áóç=–/·AL°·ç„†ªÕ‡¤mØ —­£CΚ¥Î~‚u£Q¡P˜––Öü‘šP(\¼x±••ÕŠ+h1Œ^NŸ>=yòä~ýú………iÚ˜7oÞôéÓutt8 ««ëèèXû.—›ŸŸ_VVæåå•››Û²§íõ‘‘Ë—sÊõõMâ⬦LÉõôìÞ£8P^$ ãÆ››¦ ­›;[¶øþø#O(ÐéÒ%Ž¡¡Z»—ÉÚ8† ›¬££Ö®™unÔÃã}ûöVVV*Üsû6¬Xëר15Ç\\\>ÿüs777¹\Îçóé7´yŒ1ÂÖÖÖÛÛ["‘èêêjÚÐÑѹsçκuëfΜY§€+V˜ššk—>O‚åËÁÁ|}áÜ9ÈÉ1càØ1x³–d}KKgÏæ…`’› ÆiÔ1‡oßžnôéÞ½ÝV­âHFŽÔ;{´µÕmÁï¿ëæçã{ï Vw×ÌÀ:7jnnNå )Ej*‚P‘‘µOîÞ½›NËhÅÐÐ099¹e9Ðúöí»råÊž={Öw—˚Ţ˜xm ÂÃÁÞ&O†óç!!¾ù¶lsçàƒ`Æ 7®Ñönܸ!Ú³gdZ¿[7IjqõõÏCCàpÀÔÀØx9èD,.[¶ÌÖ­306VwïÌÀ:7ZZZzåÊ==½?ü°ñ«ÍÌ`ÿ~HL„“'kŸLJJúã?lll/^L¿¡ÍFWW711ñû￟4iÒ¤I“4mŽ hkk÷ë×O&“Õw¥¥¥:í©—°0ðó{ãÈòå°|9= ``Ô{üxàó!=½–är¹H$255ÕÕÕ½×­›ñâŃ Rû(®¹œŸ?tPO¡À¹sÝÒ€Hýæ—ªªhÏnøp3õwÏ ¬s£'11Ѥö‚wà GGàpêk*//oóæÍݺuc§€[·nóT~ÒÉzXçFŒŒfÏžýv°gÊ3êkªgÏžk×®¥‚½ÙÉÇœŸŸÿé§ŸjÚ•ñòò•••oçp8^^^Úê_ncDLJJêÔ©ÅÌår«ªª Z¢U9b¿l<÷÷÷:vL3> xãF z÷²s§F `Ö÷¸nAÄǃ›\¸ðúSË"**ÊÝݽÅ-•FDDäää/Çq:::={öl^fæLÈΆ۷«ÕÕ…À@X²äõKŽ?ž0qâÄ®]» …Bã–¹G’dðС3þû‹ëÖÁúõš²…Âr S…"m÷nçÏ?×”LÀš­€×8{öìÁƒ_Oi2·nÝš>}ú¡C‡šßs|ûí·>>>{÷îÕ´!*Ó«W¯>ø `àÀ|ðÁèÑ£[†m¬¬,èܹ³‘‘‘––´P âÀÀ™·osÓ>ùDƒ>D?ýdªP<æómæÍÓ LÀF7Z\\œ““# ›ßTaaáñãÇÿý÷ßæ7Å~~~FFF Í³š¾¾¾……‹vçåúuxòRR (~ú  ¸|ââÒÒÒöíÛwîÜ9’${ôèñå—_º±sÃ]  …`åJƒµk9NÂâÅÎû÷kÒšÒRÃýûÀæ·ßÌÏÖlœÔçååaee¥£dhný“úÂÂÂË—/÷éÓç=v'–”––š™µš}Ë–‡H$züø±ŸŸ‡Ã9pà€³³óàÁƒ[ô ¯\.¿Ôµë Àå¾}°p¡fíIž1£ã±c8p §f!¥Áº-&hß¾=]MYYYÍ™3‡®Ö˜ÃÌÌ,<<|Ó¦M‡fK´ÀãÇ333k~555533+**¢êqêèèXZZvéÒ¥åNxkÎÍÍÕ××ïÕ«×Â… [ÒȺ´Ö¬ù !AúÝw5íCÉü|Û'àrÿþ£5k 3ðÖkt¹¤Nž>}zùòeDlÜŸ>|{öÀ?ÿ@\Bt4¼móçŸ~úé§:::ݺucÐèf³`Á‚K—.ñx<MÛRM»ví òòò¨_år¹¹¹y‡ìííE"QEE…P(ÌÈÈ077700Ь©M€$ÉÇÛØØèêêÊd2ªø¨¦Mkb‘(uäHËà`àós·lqþæM[ðãÚ÷î=µ²ê{þ|øÐÓÓs»Eû÷ï¿äÍÍbÍÂår_iêëë{yyQ¯ÍÍÍCBB‚ "22rĈ-n—˜˜xéÒ%###777M[DH·ß{odv¶BKKëßíGk~ð§ÈÉáíÚN÷Ë—5xªØèFÝÝÝíììèZ+œ?33“š0ÒAyyy?¦«Aæ LNNд!óú^B¡Ð % @eX<þüáÇA¸¸¸ 8…Ú‰M† aäHŸ‚¡¶¶äâE`ÍÜY–@ìß\®Ío¿µÊ¥ظ*¤¯¯?oÞ<¼rà@‰lm¯_g•:_â¼yžqËÆfp«Ø¾k6ºQ‡C¯Ë£´ô+** Xø…‹’’’iÓ¦UTTL˜0¡ÿþš6§^^/"¢l¢„Z â´µµÓÓÓKKKããã{ôèá÷–´Më ¸Øpܸ÷$’"]]Ë[· sgMô))‡6hÚÆa£€sçÎeggO:•®XôñãÇ_ºt)**ª&d‡µ˜››÷Ýw …‚å®UUU5¯)­{6––vþüyÿ€€‰DâЪË5ÌÈÈóçÛçç—YXèß½Ë. €?üÀQ(xsæ Ötð¿`©-+++,, …t¹Q>ŸŸœœÌ~7 +W®’$sssYHTTTD½àp8T¢Dvvö‹/ôôô,,,òòòÄbqûöí{õ꥞­pJ„IWW·¬¬,))iÈ!ª•¢iQÜ;yÒzút Ipw7½~èKü£ÑãǺý<|÷]k[F© 6æÔ€@ àp8ffftå5çç盚š²jîÙ0ÉÉÉ'NÔÒÒzüø±#rJKKoݺE½6226lõº¨¨èÎ;Ôk'''oooêuDDDee¥¯¯¯¶¶v^^ÞƒúõëGcvoqêÔ©ÔÔÔÅ‹%'';;;·¾eÐW¤¦Võë§_PibbËc߃6½_?§‡/´k7öe \놥£QÚõÖlll1--͹…Ŷ³³+..FÄôôt–Ø,‰ÂÂÂôõõ1;;›:heeõÖŸÇãQ¿öíÛSRÇÌ™TZZÊçó ù|¾–––@ 022b‹ö>3D?ÞsÕ*ý‚‚JwwÛÛ·y,q?{æôèÉç»þþ»¦MQ,u£OŸ> ëÞ½»¯¯/- ’$ioo/ )1s–£§§wñâÅ.]º¼ž©Yø|>A999r¹\KKË¢C‡NNN –™›î<}úôÂ… =zô3fL@@ÇcÏ{ÅvZ°€‹Höéc¬Y’~ÁgŸµCä~ò‰{KˆÛ£–ºQ’$ iÌár¹:u€ôôôáF {÷î$IþùçŸzzz“'OÖ´9 §§Ç†Š,r¹<++ËÅÅ…Ú;’ÉdˆHcx+‰ vß³g½¾þš‹˜êìì|ý:°òO. µyð  @øÿ×⼕†¥nÔÍÍÍÎÎŽÞïÆùóç먔Çn.\¸0g·qãÆi|a—¬¿è›ÚËå{ö쩨¨X´h‘……ÅW_}Õ dúêàÓO!"ª)Avî›oFíÚʼnC†¸\¸lMnÖ ä„89MèÑCÓ¶¨–ºQ===Ú'h&&&¥¥¥qqqlÆ|‹±cÇŽ5êƒ>`Ɖw#166¶]»v;vÌÏϧ¢V[§­¨€3g@"—ÑÓ/vîÈè;Ç^¤ônÞ#£Ñ÷îiÚµÂR7ZQQ¬££3¾²-%%%VVVzzzeee-EÔ‡Ëå^ºt ¤R©L&c¹ÀJAAAyy¹\.ÏÈÈèСCbb"" ##£æ´|÷îÝ›7oº¹¹M:5  ¥üûšÈÙ³PUñÚõ›o ®gO· €Å{òôé*çÌ1´³Ó´-j…¥)=::: Öh sssOOÏ®]»Ðج¸råJ—.]¶lÙ¢æ~I’¬¨¨¨ùU¡P…¦öÖÖÖþþþ#GŽtttäp8]ºtùðéJSM3@ PaU=zô033£V·[¹€cÇ€ªþçĉБ#¡ª æÍs{ôˆÍ>´âÂ…ŽééeÙõ×~\SÅå•ÅÏÂÂô¹rEÓ¦¨öºQ&Ëå/^¼(--:t¨¦mQ+W® 6¬õĪªªîÞ½ëééiggwûöm©Túþûï³|5ƒNví‚Å‹aüxÉÈ‘ºŸ‘+ ΃!CÀÝ]³ÖbšµµsQÑ“I“züý·¦­Ñì%I$’ŠŠŠ×׿šUuçý÷ß—Éd46«–-[¶lÙ²7jÚú!I222òŸþ€þýû»¹¹1BÓFi‚ÔTxð´µ%%qÒ?ý&N„pt„/¿¬^6exé’sQQ€ñwßiÚÍÀÞIb@@À¨Q£è åñxÑÑÑ46¨N–,Y6švèE"‘„††J$’Þ½{wèÐa*K `¨âèQ" r„^^N¡¡°õ9==6 X(ÚÈY·tÖ®µn º?LÀÞI=C”••ݺuKKKkìØ±š¶¥‰Á†0Òæ“‘‘qýúõAƒ¹ºº>}ú”Ïç·šÊHM@&“å[X8TV"—Ë© ‡07‡1c`üx`gÈ}ÎîÝv_~©°±ÑJO]]M›£Ø;©ñâÅÎ;¯_¿No³=š0aB`` ½Íª½{÷:99½xñBÓ†4 ªèHNNNVVÖ£G {÷îï¬í˜‡ÊJà$8:ÂâÅpãäçCPL˜ÀN $‰k×ÀÙ.]ÞY lžÔ#bIIIYY½ÍöéÓÇßß¿åj¡§¦¦fggÿõ×_¿üò‹¦mi b±øêÕ«………óçÏïÝ»·––Vw)k°N„BááÇ—fgƒ——hØ0ƒéÓá¥ð Û9uʾ¼¼ÄÀÀ7(HÓ¦höNê%Iee¥±±1]’£­ƒÂÂÂŒ7NÓ†¨ŒD"ÑÑÑ‘Ëå»víªªªš?>Ó:¤-D[[HKS»¥u!“YîÚ·ßZQµê¦Á^7ª££CIŽÒ®Ïæçç7wîÜ–UÃårgÏžíççgnn®i[¢¤¤dÏž=ÁÁÁ$IvïÞ}þüù£FÒ´Q,bÉ’%W®\Yºt)ÔW¡:&¾þºúõ‚pô(¼¾5:p p8Àá€FbN‚‚ŒŠ‹å®®ÃþüS½³ M‡¢¤¤¤ªªŠ$IMÂ: …¦MhˆììlªÊñ®]»¶oßNUCi£‰D‚ˆ………Ó§O/**ª÷º+ úçÔ)DIJ2<}ºúì‚Õ§V¬PƒÍo ‘”#¶¨•%æ`ïhÌÌÌôôô˜‚¹sçΗ_~yíÚ5Ú[V<O"‘úúúRÁCìáÊ•+|òä —Ë>}ú_|ÁòQ³šyøð¡ƒƒCpp°¥¥epppCµžŸÿÛo¿éêê²AÌ_ ˜˜@a!ýæÖ …å¦ Eñï¿[Ì«¶~Y«Ý““S†cÇŽ9sfõêÕ½X(÷ 4ÉÉɽzõâóù)))Í,ÔÑþþûï„„¹\îëë;oÞ¼¶§]hkk#"A$I6¾ÐafÓ¦Á¡CŸ_}dölppxCÊSK :wKK¦,®‹¢~°R(žhk¿×b]˜€ÕŸûèèèk×®¹»»0Pð:,,ìôéÓ={ölÑn´cÇŽžžž–––B¡P=nãââ¤Ri=úöí+‰ìííá]¨íÑTBBBÜÜÜüüü>|èáá¡”†ÿgŸ\¼øÊ.Xµ3˜Õ,W&Z€N` í'[4¬þèóx<¡PH{Z=ŬY³úöíÛâdðkªÎ…ÈìììS§NéêêvéÒÅÙÙyþüùjëº%ríÚµqãÆ988DEEuíÚUÓæ¨Èúõ ‘Àúõ”ìHú’%NÅÅ0p ûÒ¥š¶Œ]°zmT.—K¥RƒwYøGŠŠŠõõõ7lØÀP·nÝ7nœžžÞéÓ§½½½ß‰âHÍC$=zìØ±Ë—/WùæîÝáÙ³ê×wïÖ1ecc¨¨€òr06&‹ŠD66F$è»zµº-a7¬v£LóÝwß]»víäÉ“NNNš¶¥YDEEùøøèëëggg›šš2ÑÅ_ý•’’âçç×¢ÃÔÉöíÛ---gΜ)•JuttšÒ„ÆÝ¨¡!ˆDPY ŠÕ«µ~ù%ÂȨ{q1ÿÏþ| VOêe2ÙîÝ»årùjfž~±±±áááwîÜiénÔÛÛûÿûßðáÃéõ¡Tu9mmíÁƒ:ÔÊʪ_¿~4¶ßŠyðàÁÒ¥Kù|¾¯¯¯³³³¦Íi*Àã‘Öž=Ð+$¤-ƒ¾6¬v£ÚÚÚUUU …B.—3ñüöÛo—.]Ú:ô.¿úê+ÈÌÌär¹ÔžOs ª—••=|øÏç÷ë×ÏÖÖÖÖÖ–K[?$Iöë×ïÛo¿uttlÁ>(9 .7zÎ/‘¨´o_3*H9&BB  Ë­Mf¢*Ayy¹\.×´-ƒãÇëèèÌœ9³™íDEEmß¾½¼¼ÿû¼<:¬{' Iò³Ï>9r$•5ß\ºu{•S÷. ª ‡˜‘!årI€M›@}}äpðÊ ˜ÄJؾE`llÌ\$ "Nœ8ÑÆÆ†Þú£š¢oß¾ •J j.¦:Tz~RRRiié“'O`À€íÚµ£ÑÈÖMFFFppð­[·˜­òrû6øøÀÅ‹ vAAF·nÕ&Ét/¯a À¸q°p!ˆÅðå—0x0ã´X=©€sçÎEGGOž<¹sçδ7Îáp233 ž?777%%E&“™››¿ãÕåTE"‘Œ?¾W¯^ñññýúõ6lS=™™Áþý°~=Sí¿I"råò##øøcÈΆàéÓ6úl>< €¹ðrjI&“µšŠO‡ ÊÍÍmT/]ºôäÉ“Ï>ûÌÒÒrÆŒm±,M€$I¡P(•JéL‰‰òòW¿†‡ƒ½=8:‚ÚoÔÒ‡#°./V­‚lÛ©¯ ÛG£úúúŒ¦è”••yxx888`k‰Ÿ]¾|ùܹswíÚÕÀ5b±¸¢¢‚ÃáPrvYYYàââÒæCUE,‡„„èëë_¼xñöíÛÔò4 „…§'¤§¿:²|98;ñcô´¯ ’ÔE Ÿnó¡uÂöðû˜˜˜³gϺ¹¹M¨Q«¥‡ââ⸸8GGG†ºÐñññ]ºt©=7ONN>}ú´³³ó”)S*++©Y¼F,lé(Š#Fü÷ß§NbîóYññàæ.À˜1ÌuR‘—gD…¸ ýu–ŠjØ?ÕÕÕetm„Ba+ó¡+V¬ððð8}útÍ‚ ’““ÀÆÆ† …BA„¡¡a›m2ZZZãÆsqqi¡ÇoñÇáà €ýŽŽÒæCA“ÑVJ@=!x ¢P(²³³™îEìÝ»—Ïço¢ý ‚Ø·oßúõësrr‘Š m£É‚Å‹K¥RÔÈ›‡xᣈ‹‹O,^|çÎF{i°}‹‰Ëå61YiâââúöíkooÃhGêäã?>|¸««kVV–®®®••U§N¤R©D"cccMز™4iÒ½{÷´´´¶nÝÚ*ßÌØØØ÷Þ{oꎚ6¤eÀöI=I’?ÿü󯑱5\™L†ˆR©”¡.Ô¶¶¶««ëùóç>L•œ0`À_|áââ¢iÓZ;vìðõõ]µj•¦ a„¢¢¢¾}ûvíÚµŽú=W¯ÂèÑ`e<èêÂäÉš0u°ÝRRlAˆÅb†ºÐÑѱ±±L{ÕFYYÙ½{÷ñÇ,--ÍÏÏ'I’Ïç·U—k&111]»võöö¾wïžúW >„o¾µkvì€U« $„öNÒÓÓ­­­]\\ÞhoÙpù2”–ÂG­-¤¥ÑÞ{‹DË J ‹ÕPª>???))‰é^Ô€B¡Ø²e˺uë/\¸°hÑ¢ÜÜ\MÕJ˜9s&L™2EÓ†0ŽL&ËÏÏãPt4r¹Õ þŸ~Šˆxò$öìY}vÀ€êScƨÛVÀöµQÐÕÕ¥’Ä™L]¼xqìØ±Ã‡¿zõ*C]0B¡ˆˆˆ°µµuttìׯ_~~¾µµu§NÆŒ999MKmƒ¢  ÀÚÚú·ß~sppX³f¦Ía_~ù¥}ûö3f̰¶¶~ãÄT§ØÀ!#F¼*ûÜ¥ ܹ öjÏì€í“z8{öìÆããã™ëÂÛÛ[OO¯E×~üøñÕ«W¯]»†ˆ¾¾¾&L011±XgfÓ¦Á¡CŸ_}dölpp“W×hiAçÎ`i©&sYF p£ÔN½L&c´—=z0º‹ÕLd2ÙíÛ·SRR.\èíí-‰TvppX´h‘©©©å»úAW‰“'OvíÚÕÝÝ=22òÿ×ÖÖŽŒŒ wuu}ûÜgŸ\¼øÊ.XPG™Òèh†md/-`m”$I’$Õ°,•}ÿþ}¦ûR™LÆãñ8Ξ={JJJfΜYÇ]$I‹ŽI`šË—/;ÖÚÚ:&&æÑm‰‹‹»víÚÂ… õôôê½HãÕžYL xâr¹ZZZLFà·ß~›:uêÑ£G™îHyâããwïÞýäÉ.—;f̘ 4LJ&''>ü£>¢ÑÂÖLj#&Nœ¸aÆwćÀÚµk—,Y²aÃMÒRi“zøùçŸÅbñÚµk“¾ÿþûÆ cI "¡Phll¬P(„Babb¢OóKõÞ¿ßÀÀ °°ÐŠ ýkã5~üñG##£¯¾úêĉTò;Â'Ÿ|RTTDÕèn£ ´€I=lÛ¶M*•~þùç­RMç-ªªªNœ8QZZºxñb--­¤¤¤N:ÑïuëÖ-###ZZkMDDDôéÓ‡ËåÆÅÅuêÔIÓæ¨eyÚ&õõÓ2¹Ë–-ûæ›oÔàC###úé§ÄÄD¦;ª@ —Ëõôô¨ÚEEE§sçÎ4ÆÌ<ØÈÈ(44ôÑ£GtµÙÒAD™LÖ«W¯mÛ¶½S>4<<¼C‡{÷îÕ´!-›–1©‡—;-ÿßÞ}Ç5uõ¿!„=A!," ‚‚‚ ‚RAeº«V¥Nú(ô±ÚçeµúÂñÓV[E´*V«RŠp!Š¢"ˆÊ” !ì’AÖïQQAvîD¼¼dð16zÿþýœœÿ)S¦€Î"KL&ó·ß~CdÓ¦MšššÒÇJ˜µ.]€¡TÏRúêé马¬tpp())iooŸ¦|ƒ}‰‰‰sçÎè@ù§ÆF½¼'Oþ»Ê~çNäàAäÝ;dÌòÊ/|ü Íš5kûöíØÔÐË—/óÍ7ͽ3Q ‰òòò¸\®žžž©©©™™™tã,khffæäɓϟ?Y‹r…ÇãÍŸ?ßÛÛ»°°ÐÁÁA khFFFxx¸«««tʡ۹ó¯J–.E8äþýáÇÃ|”QA0XÈ$uîܹãÇ?•nžˆŽ;wîܾ}ûùóç‚,]ºtùòå¨öâ?ŠF£½yóæÜ¹s·+'ˆD¢ô6›*9D¡Pf̘9 ç EEHW×_Ÿæä 55ˆ´#;kÖ__Aú™Ã¯ ðÑ©¯¨¨HLL3fŒtûqT]ºt©¶¶vñâÅÃ\,ôOõõõmmm'Nlhh¸zõêÌ™3?²VÄbñÅ‹—,Y‚»í‡©««ëÎ;Ë—/çr¹uuuv½;¼)%‘Hôù2úüùǧ7%&"Ë—ÿÏWÎCÖ¬Aªª33™EÄ|~ü8;;{åÊ•¦¦¦‹-255ÕÑÑÁ,ÔÔÔüýý Bgg'è,2Àår…Ba}}½D"›"B$ïÞ½{úôéE‹΢€pÓ©‰DÒùðØ,6›M¡PTTT Fï+@Àápôõõ322²²²üüü¼hO06›­¡¡÷­ó=zäææ¦§§—••åå奴ûWõÅår›››---AQX¸ù!«¯¯ÿù矯\¹‚Ms:::>¬­­í­¡ ñññ)))‚xyymذA‘j(‚ :::"‘èðáÃK—.eˆnݺÂçó½½½a •:yò¤Ý¡C‡@QX¸ù9ÓÑÑÑÒÒÂòQòôéÓFC„B¡ôôôp8.—«®®>jÔ(Ì’`†Ë寯Æ&%%átÍÝÝ}̘1êê꠳ȑšš¡P¨T‡£` 7zìeggGFFèëëK'-·µµ(öXÛÙ³gõôô,X€¯?æ‘#G&L˜0cÆ Œ·¾Æ‹ÒÒR;;;|ýânîFáñxØÔýææf"‘øáÇÊÊJ]]]é®”††† ÿƒ¸jÕª… ²X¬ÂÂBÐY*555&&fîܹ­­­°†öÕÕÕµjÕª>ØÛÛ+ü.@xzžpüøq&“ùïÿí_•²²²K—.Q©ÔüüüqãÆÅ›—ÞwïÞùùù5êýû÷¸˜¿5{ö쯾újÆŒ#GŽE¾üúë¯üñG]]Ý£G@gQdx*£ …@ HÏÛ@Ç{ÿþ½›››•••¾¾¾‰‰‰££#@àp8JUFtuuuuu[ZZ¨T*è8Ÿ$‘H¢¢¢ÔÔÔŽ9)}Tdd$F‹ˆˆDÁÁ±Ñÿ’H$'Nœhnn^¼x±£££t}ç… Ö¯_¿råJeÛˆN§›šš‚NñïÞ½sss#ïÞ½³··GîÀEŸ˜ÁÓØ¨@ hooïîî–á5Åbq^^^YY@˜2eʘ1c ‘NŸ´¶¶æñx2lLMM ÆöíÛ@gù¡PØÑÑ1a„K—.¥¤¤ÀúOíííVVVJ{Ø–ðt7zÿþýììlNØ|ÿþ}rr²¡¡aTTÔ?§ŠD¢îînå|jqëÖ­¹sçÕÔÔhhh€Žó.—»páÂÊÊʧOŸ*óîËý»qãÆÒ¥KýüüîÞ½ :‹âÃÓØ¨žž™L–É2:ž››2~üøwïÞ999}ôeD"QOON§«ªª*ÛolHHȆ –,Y"W5A6›]YYÙÜÜ\__¯l)7þüÊÊJx+Š <ÝÊŠD"9vìX[[[hh¨««kÿ/þñÇwïÞ»cÇlâÉ›ÎÎN‰$›p¹ÜÂÂB77·ºººÖÖÖI“&N$§&Ožìââ:ˆ²ÀÓØ¨X,f2™íííC{{WWWJJJ^^@˜5k–¯¯ï@Î7vtt400Àlg)ysáÂKKËýû÷ƒ‚p¹Ü   __ßììl XC?…F£mܸÑÍÍMºúž:õMMM§N¢R©ëÖ­ÂÛétz~~~uuµ‹‹ËرcÇŽ;w-\¸ðË/¿TÚ©Ëööö,«¼¼tDCCcüøñ4Mžç`É--­õë×wtt˜››ƒÎ¢,ðÔ©ïêêJHH066 à[Äbñëׯ߾}©ªªúèÑ£I“&Q(”AµËåróóóÇŽ+}ˆ¯lJJJhjjúý÷ß·mÛ&‘HÚÚÚr7YQ’ å ž:õúúúß}÷Ýk¨X,‰DÒI…%%%ÁÏÏo°5Aˆˆ//¯Û·o>²"pppèììܶm[mm-ö­‹Å €íÛ·@Û·o÷ññ‰Dá ŒJÏàü(±Xœ››'-pÁÁÁ›6m3fŒÌ3.\¸pĈ2¿2Žôôôðùü§OŸ¢ÚJVV–¹¹ù­[·ŒŒŒŽ?®­­jsŠA"‘899™™™-\¸te„ƒN}CCC?ße³Ù—/_ž8qbhh(f‘”ƒÁhhh7nª­üðÃûöí ?þ<ª )8Û y¿ýìò!CCؘ jèƒ8ð©áe@&“ÇG£Ñöî݋ƿ¾ïß¿—H${öì9{öìÙ³ge~}E•íîîž‘‘k((ò^FUTTúÔ®¦¦†ÍLQQm¼˜­IIDATQÿùÏ 0hKn‰D"ooïíÛ·ß¼yS¶W¾s玻»{tt4@X¹r%¬wøðáׯ_ÃýíÂÁ\H‰ô©j‚––61–.]Ê`0äa‡€ˆDâþóŸ×¯_Ë|I»tÆ…P(”H$pŽÚ œ9sÆÕÕuíÚµ ƒ(/Œ …–––~KGGG97•<O&{èݸqÃÓÓÓØØøýû÷NNN°†Ê‹/<==A§PvòÞ©GDUUÕÐÐðo½<€q åñxgΜٲe f-Ê-&“9aÂ@0ÌK]¹reÑ¢E3gÎär¹ÎÎΰ†JffæÔ©SáÃUàpPFQSS322200ÐÖÖÖÒÒÒ××§R©߇’H¤˜˜˜ƒ677cÙ®ÒÖÖÎÉÉ©®®ÎÎÎæ¥æÌ™3yò䘘MMM™dS*---FFF ƒ(;têåGll¬––ÖªU« @gìÍ›7#FŒ°´´òöìÙ3~üøyóæñù|¸|È8ŽŠŠŠ¼P l`…†®¨¨¨¼¼|Þ¼yƒ}ã½{÷æÌ™£¥¥UYYillŒF6Å&‘HÂÂÂ.\8þ|8,£ƒÐÜÜÇçó<: x………&L “ÉUUUßj@"‘H$•˜˜ww÷¯¾ú ÕŠêöíÛ¡¡¡T*µ¢¢³É*ЧÀ2: ÃÀÀ@MM­«««wKeæççgmm½oß¾nh-V­ZÕÓÓsñâEeÞxpøø|þÉ“'õôôV®\ : Ëè íÝ»×ÑÑ100–Q¤ÏêÃ.C,--uww‹Å999h/*U`t:J¥Âå,£Ð°”••mÞ¼ÙÚÚúÈ‘#ý¼ŒÏç·µµ™ššfff’H$///Ì*‘Häìì,‘Hnß¾=œÍÈ!‚ÿ  NqqqXXØ·ß~ :ˆ¼àóù©©©.\`³ÙŸz ‹Åš5k–‡‡GMMÍŒ3` Žºº:@ÐÓÓcaa: ô_°ŒÚŸþ™œœ :…¼prr:}útaaa?ËdÅbqww7ÇëêêÂ2›B²²²***JKK#‘H ³@ÿ;õƒ#‹OŸ>íêê:yòdÐYäKVV–‘‘Ñߎ­f±X/_¾ô÷÷okkkiiã¡Ãtýúõîîîå˗í[ä‹‚†MºéúÂ… û~‘Ãáxxx¨ªªÞºu T0EÂçó¥ë’““AgþìÔZzzº——׎;@‘#óçÏ744´³³“ôéÜhjjŒ7nÊ”)³) "‘¸gϞŋÏ;tèÀNý Ý¿öìÙ/^¼EŽôÝð‰F£ýúë¯?ÿü3‘Hd2™p®áãñx‰î< ŸàÝè M:õöíÛ©©© ƒÈ ¬¬¬©S§>|ø044ô×_ݳg‚ °†ÊıcÇlmmoܸ:ô°ŒšŽŽNpp0…Bþ6q &++ëÅ‹¿üòK||üôéÓ7mÚ:‘âHOO§Óépч|‚et(Nžè,।¤XXXœ:uJOOoïÞ½¡¡¡†††Ÿ= éÓ§»»»ÇÄÄ€},£C´eË …W…"R^^Îçósrr¤Ÿ†……UUUEDD€M¥D"‘¯¯ï«W¯¦M›: ôI°Œ‘¾¾¾@ ¨­­¤ììl@ðÝwßݼyóÔ©SÒ/‰D]]ÝGÍŸ?ŸËå‚Mˆk­­­666‡‚“»åØETøÕÑÑÁd2A§éÚµk$髯¾‰Dû–H$rqqA$..H6ÅpøðaAA>î@>DÒÙ<4ÍØØX9÷Ú±µµÕ××wvvþçþÁ***‡*((X»v-lŠ!::ÚÆÆÆÜÜtè3àbСóóó{ôèÑÓ§O½½½AgÁÔ±cǾøâ ‡ææf##£~^)‘H>|ø`ooY6…ñðáCwww¸ àØèÐ988755‚©Ë—/ÿë_ÿš={vwwwÿ5”Åb¹»»»»»K§CAG£ÑBBBlll è,ÐçÁNýÐ:tèèÑ£ S`mÁ‚ÁÁÁË—/×ÖÖîÿ•ºººÆÆÆíííÕÕÕ£FÂ&žbàp8S§N522"“É ³@Ÿ;õÃÂáprrr¦OŸ® g…ÿý÷vvv‘‘‘b±x€ç©µ´´Éd¸|húnšÉ3XF‡ÅÜܼ¾¾þÇÛõ]ñdffúúújjjVTT˜˜˜ ü‰äÊ•+¥¥¥;wîD/ž"‰ŽŽ&“É›7o†£xËè°|ùå—õõõqqq |¦ˆX,‰D$éÈ‘#vvvsæÌÔÛ«ªªìííÅbqQQ‘J!N·´´$ÅÅÅcÆŒXF¡þðx¼%K–ðx¼”””!w0÷îÝkii¹lÙ2x´ú@¼|ù2??Æ  ƒ@Ëè°ˆÅâ>”——‡††‚΂Šêêê)S¦ôôô<þÜÑÑq8—ý?ÜWr555jjjƒ3ä,£ÃÂçóÉdrOOOGG‡¾¾>è8²Äápètº­­m~~¾H$æ¨E^^Þ’%KlllîÝ»'«„ŠgÁ‚÷îÝ»xñ"|(«k*Œ×¯_oÚ´‰F£™šš‚Î  Q NGDOOO(‚Î2\<oüøñáâÅ‹h\ÿĉ‚¸¸¸ˆÅb4®_³fÍBdÇŽ ƒ@CAܵkØ:Žwººº………AAAžžžx_®£ªªª££ÓØØ¸k×.4ÖÏ899½ÿ~Ó¦Möööʰîkà¦L™Âf³wíÚO¢Ç#ø¤B©¬¬Ü½{÷‰'444ø|¾ºº:ªÍ±ÙluuuåÜ`ðŸèt:ìËã¼•ÆÆÆÄÄÄ¢¢¢‰'‚Î2‰dÖ¬YÒã<ýüüTUÑ}ðxñâÅÀÀ@ …2iÒ$TÂ…G¹¹¹q8???ÐY !‚˜d ¾¾>**êÀ ƒ …X,&gÏž;wî¶mÛ0hQUUµ¥¥%55ƒ¶ä_nn®D"Q¤ÙrJvêe §§gåÊ•^^^ß|ó è,ƒ“••~õêU,ç*ŠÅâôôô€€8<*UUUell¬¥¥:4DðnTÔÔÔ.^¼ˆ»Š ÈéÓ§kkkÏœ9ƒe£***l6{ïÞ½]]]X6-W$É–-[JKK­­­a Å7 óGaaáÖ­[OŸ> :È@UVVJ$>ŸèÐ! Sµ¤ëwî܉}ÓrâÚµk‚XXX(ÀT9%1ÉÆ‹/6nÜÈf³qq>ûµk×|}}I$ÒôéÓ===¬,233+**Z½zµ••ö­Ë]]]‹µdɸúïàbPÙðòòúᇼ¼¼@&“) ëëëf˜6mÚ«W¯eÝãÇã™››'$$€É|Ĥ\ÒÒÒ|||´µµ¥šȳk×®øøø7oÞXXX€M‚%‘H4qâD—Ç1th¸à#&™IKK[²dÉåË—Aù¤sç·„„…Bà5A²²²öööëׯƒ‚©¼¼¼òòòçÏŸëêê‚ÎÉìÔËLmmí•+WH$ÒÒ¥KAgù8???++«eË–¡=Á~àvïÞ½víÚ3f€‚)ww÷ŠŠŠ††¸ŽK1ÀN½ÌTUU=xðÀ××W·Û¿ÿ_|áîîÎb±ä𨩩éîÝ»_ý5è XHOO9r$\Á¥H`U|IIIK—.9rdEE…6Éår-,,ÚÛÛsss]]]AÇAŸÏ;v,FËÌÌôññ’ 86*K¿ýö›››Û;w@ù ,˜?þáÇ将"¢©©¹råÊ9sæ(ÃæF=== ,puu6mè,ÌÀ»QYúñÇwïÞ½uëVyX_/ W®\I¥RþùgÐY>C$‰DÐ)°£l^…˨,•——×ÔÔ¸¹¹ÉÃqCÙÙÙ>>>šššEEEò?¨³³366¶´´4-- t´>|øÁƒ{öì‘ÉñVü€eTñù|.—K&“­¬¬p±(€ÍfÛØØ´µµåææ*d•‹ÅeeeiiisæÌ’%XFeì›o¾¹víÚÝ»w‡y"ñ±X¬ààà®®®ÇS( †æöíÛ£Gvvv-—.]ŠŠŠ’1øˆIƸ\nKKKNN¨L&³¶¶–N§766‚Ê04!!!ÎÎÎ ¹¹¹ ³È“É|úô)…B5T!Á»Q+++#¶¶¶Ø7Íb±***\\\ÊËËù|þøñã±Ï0L/_¾œ9s¦™™Yaa¡"MMݹsç÷ß¿ÿ~ÐY Ù“—Õ, C:÷¾«« ãýÌ™LæìÙ³KKK322ð;¶8iÒ$ 7776›¯‰þéèèŒ1"88tðnTö¦OŸþìÙ³ÚÚZ333Ì•H$6lÈÎξwï•JŬ]™SÔ Ÿ¸\®2LŒUNplTö´´´TTTŠ‹‹±i®®®î§Ÿ~"ñññ¸®¡‚hhhÔ×ׯ[·îèÑ£ ³È@ssóôéÓÓÓÓa U`°S/{¿ÿþ;…BÁæ×F øûû—••éëë¯[·ÎÐЃFÑöîÝ»S§N™˜˜¬_¿ï#¤qqqOŸ>ÕÓÓƒ“œÜý^ötuuI$R]]ãD"qôèÑííí{÷îUSSC»9lŒ;V]]]1öâôððÐÑÑY³f Þ{ P?àØ¨ìñx<++«ÎÎNƒÞ0_qqñ÷ßÿçŸêéé‰Åb  ídž†† ƒ QII‰ƒƒèêðw8 CCÃQ£FÑh4ôZY³fÍ;wöìÙƒ ˆBÖУGŽ?~ïÞ½ ƒ Qmm­‹‹‹··7ŸÏBEųgÏÐëÑK÷ MJJ:pà@ll,J­çíí­¦¦¦®®:ÈÕÔÔŒ5ÊÜÜ¿h€`§-L&“F£9::Êö²)))aaaW®\ í•åPgg'®gòx<6›­Ïý ~(`gPTWWS(”Y³fÉüÊ>d³ÙwïÞ•ù•å…B)..^¼xqYYè,ƒ³sçÎk×®©««Ãªd}ð=$‘H$b±ØÒÒÒËË‹Á`Èêšoß¾•H$"‘èÌ™3"‘HV—•s«W¯F$,, tA(--%‰$©ººt °SIIIááá[·n•>SRt:=..nëÖ­8z^ßÓÓsòäÉÆÆÆ}ûöÎa>bB‹D")**b029.B[[›@ ÈÑÈ355•%€—ÉC]]]ººº7nÂEKff¦““Sttô0¯“””ÔÑÑ\\\¼{÷n™dÃððpGGÇììlÐA>oõêÕŽŽŽ¯_¿Â,£hqww;v¬‹‹Ëp†MΜ9³lÙ²Y³f ÆÃ[[[ÒÒRÐA>ƒÅbÔÕÕ™››ƒÎaŽÊ5ƒáïï¿yóæ¥K—‚·Ãár¹¸ …oÞ¼qwwÂ,£(jooÏÎΦP(Cݶm›¯¯¯¿¿?ŸÏ‡ó·¥ž?~þüù'NÈçq^^^AAAxx8<õSé' à.]º„ HHHÈ`ßxõêUAÈdrgg'Á𨧧ÇÔÔA+W®€Îòq³gÏFäÀ ƒ@Xƒ;<¡HOO¯¤¤Ä××wêÔ©|‹X,Fdܸq [¶l™8q"šñ„H$Ž1ÂÁÁ!<<\>÷î$ÍÍÍ”Ïxz`§^Žðx¼%K–&$$(än#²B§Ó¥w¦òCQ7í‡þ®¢«¼¼<..îÉ“'yqIIɃ’““kkkцS­­­Ó¦Móððàñx ³üåÞ½{666çÏŸ–Qtݺu+:::11±ÿ—q8œ¦¦&—äää‡ZYYaw Øl6‡Ã),,å/—/_nhhhhhvêÑ•ŸŸüøñÐÐÐO½¦££cöìÙ #++ËØØËxxT\\lbbB&“Aù‹X,¾~ýz@@€ŽŽè,°Œ‚×ÖÖ6cÆŒŽŽŽÇÛÙÙŽƒ)))---kÖ¬C"‘\¸paÑ¢EZZZ`“@Á2Šº‡¦¥¥-[¶lòäÉûV[[[AA¯¯oCCCww·­­-„¸“››ëææ¦§§WYY v'ºëׯ/Z´hÒ¤I¹¹¹c@`Á­IP—žžþË/¿èêêþ­Œ2™LŸªªªÔÔÔ/¾øT<<š©ï©©©/^¼hnnþöÛo1n’7ðnEoß¾­ªªB¤¢¢bäȑҳB‰D"@ˆ¿~ý:¬¡ÃôàÁP7ƒ©©©b±888Hëü€e- /_¾üè·ÔÕÕƒ‚‚0Σ¨„Bá¹sç&Mš„åþoß¾µ¶¶ÖÓÓìEHžÁqq´|ê[|>.÷”•Ÿ~úiõêÕ?üðf-òùüyóæYZZ–””`Ö($Ï`E ‡Ãéç»pá ¬¬]»ÖÉÉéË/¿Ä¬Åööv[[[sss¸V’‚˜ÐÒÿh‰@ À,‰b344|ÿþ=‚ "‘›ý’MLLüñǨ¶ÂãñvîܹgÏž¬¬,T‚ð>©GKWWWFFÆGÿ÷êëëÏœ9ûH ŒËåÞ¼ysÉ’%hw´_¾|™œœüÓO?¡Ú „/°Œ¢¨¡¡!''Gz.H/}}}___8¬†@””´lÙ24I™L&‹Å’·]÷!y™Qdbblkkk`` §§gdd4eÊ”™3gŠ’àààððp”ºö¿üò‹­­í©S§Ð¸8„kðI=ºTUUœœ@§PÍÍÍ–––h\¼¦¦†ÇãÙÛÛ£qq×`§RÒÓnÑ»Ù/))qpp@éâ~ÁÞ%¤8‚D"ùí·ß&NœÈb±duÙÖÖÖo¿ý–F£Á },£B!‰‰‰‰ïÞ½KJJ’Õ5ÿïÿþïðáÃp''èSàØ(¤hŽ9ÒÖÖ6gÎY]0**ª¹¹yëÖ­²º ¤`àØ(0¹¹¹uuu½Ÿ’Éd …ÒÖÖÆårÅb±ººº¡¡¡ÜFhhº»»_½z5üÓY \°õvêquuí{¬‹Å"‰nnnd2™ËåÒh´Ç·´´ ‰S¶¶¶ÁÁÁõõõùF377ŠŠúÛä_ê –Q`TTTúÞijii9;;›™™Q©TOOOér‘H”——‡‹B¡øøøxxxtwwç:<Éd©¾P?àØ¨>¾¸¸ØÚÚÚÌÌL¶Ù ïF唦¦fïÇÃì™*­ŽŽŽ}ûö ‚ÿûß666ƒzoIIILL ‰Dª¯¯700@)!¤`•S}7× …“à×èÑ£80nܸÁÖPAÈdò×_M"‘` …> –Q9Õw"Ú?Ÿo´¶¶Œ7ÎØØÛ\8 Hkk+ƒÁ°µµà»D"•J=yò$šÑ ÅÇFåTßSFú ÜÝÝýæÍ›êêjƒ"þdddØØØ¬[·nàoY¶lYXXNG/¤H`•S}OÄë;ý[MMÍÅÅ.î8WWWUUU"‘Èf³òúÆÆÆÛ·o߸qƒ@   R °S/§ÚÚÚ¤*•Úûu‰(^‘Éä‚‚‚o·L¥R+**òòòà$3h€àݨ>>** ûTÞÁ±Q`Äbq}}}nn®ôSMMM///¸µ%Ú***öíÛ÷óÏ?K×ËK$’W¯^yxx€Îáü&??¿·†"Âår>|øìÙ3€‘”DLLÌÙ³gúé'é§7oÞôôô\±bØT~ÁN=0“&Mê{ˆ„™]»vQ(”ÞUö#FŒðôô› Â/Ø©‡”Qkkkkk«ôȦQ£F±X, ¸Ðx7 )—†††ÜÜ\@pëÖ-SSÓÉ“'‰D ÐÑ ¼‚w£iiiùÔè³›››¹¹9Æy Å1AJ¤ï3½¿yûö-–I EË(¤,8ÇûÔwAï®Z4(°ŒBÊâ³U²wWXF!eÑ÷”À¡½‚> >©‡”…¡¡a?ß%ÿÜî>77·®®®÷S2™L¡PÚÚÚ¸\®X,VWW744´³³ÓÓÓC%1„ðnRÒ]\?õ]mmíîíäêêÚw‰‹Å"‰nnnd2™ËåÒh´Ç·´´ ÂXF!%âééùÑ9öD"qÚ´iÿüºŠŠJß;M---ggg333*•êéé)‰DyyypŸCeË(¤DÔÔÔLLLz÷QQQ122 ìWêêê½kq¹Ü¦¦&g…ðŽBÊEUUUº™SOO‚ jjjC¾”¾¾~CCƒôãöövx’¨Ò‚eRRÃ) Rššš½wwwój~ÁN= Qß RB¡`,XF!hˆúîG7ÛVfðH ô~¬®®0 … !âp8½“ÉäÞóòò †¦¦¦t”ƒƒC?óU!Ë( Qï|@¥R{¿Îf³¿øâ € HIIɳgÏfΜ©££&%„>Ø©‡ ¡hkkëÝëdôèÑ}§ÚÛÛKk(‚ fff"‘.sRlðn‚ª»»ûùóçZZZ‰¤¾¾^úÅ‘#G:;;÷}Yßó®¥ýz¸é‰bƒe‚ŠD"‰D":.¤+ô-,,,--{ï=ÿ‰Á`¨¨¨Œ5 ËœÆ`… ÒÔÔôññøëÅbqEE…]߉úâc£4PƒÝäÝ»w#FŒppp@)$'àÝ( ÔÀÏ”H$ùùùššš°†*XF!HÆ„Bann®™™™™™è,`… O‹Å,«÷S¡PÈd2uttúYúÙÓÓóìÙ3*•J"‘𛛥_TWWï;?R0ðœzú¤¼¼¼ÚÚÚ¿}ÑÐаŸMíííOž<ùÛ§N*û||€e‚ hXà“z‚ ae‚ hXþHêŒñn£õçIEND®B`‚opengv/doc/addons/images/absolute_noncentral.eps0000664016516101651610000012622113344612246021047 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/absolute_noncentral.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 11:52:42 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 899 727 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -15.005600 -33.313802 translate %%EndProlog 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 28.676300 19.654200 m 30.650000 28.000000 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 37.050000 10.950000 m 44.990600 12.499700 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 24.500000 18.200000 m 23.802900 26.160800 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 24.950000 12.650000 m 16.578252 16.535515 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 42.525000 27.650000 m 33.890542 33.125056 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 34.084508 32.706041 m 33.796121 33.184928 l 34.352263 33.128305 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 42.500000 27.650000 m 33.342372 22.629297 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 33.802953 22.596705 m 33.244336 22.575549 l 33.562581 23.035135 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 42.550000 27.700000 m 42.550000 17.123607 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 42.800000 17.511803 m 42.550000 17.011803 l 42.300000 17.511803 l s 0.000000 0.862745 0.945098 srgb gsave 37.578800 18.250300 translate 0.035278 -0.035278 scale start_ol 2333 -128 moveto 1934 -128 1649 -32 conicto 1364 63 1183 230 conicto 1002 398 917 628 conicto 832 859 832 1130 conicto 832 4416 lineto 182 4416 lineto 182 4776 lineto 948 4992 lineto 1570 6144 lineto 2368 6144 lineto 2368 4992 lineto 3414 4992 lineto 3414 4416 lineto 2368 4416 lineto 2368 1211 lineto 2368 864 2512 688 conicto 2656 512 2891 512 conicto 3072 512 3250 538 conicto 3429 565 3584 597 conicto 3584 163 lineto 3509 110 3365 57 conicto 3222 4 3049 -35 conicto 2876 -75 2687 -101 conicto 2498 -128 2333 -128 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 0.000000 0.000000 srgb n 16.340200 16.646000 0.212500 0.212500 0 360 ellipse f n 16.340200 16.646000 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 16.340200 16.646000 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 23.802900 26.373300 0.212500 0.212500 0 360 ellipse f n 23.802900 26.373300 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 23.802900 26.373300 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 45.203100 12.499700 0.212500 0.212500 0 360 ellipse f n 45.203100 12.499700 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 45.203100 12.499700 0.212500 0.212500 0 360 ellipse cp s gsave 22.505400 27.674000 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 15.005600 17.885200 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 45.462800 13.847900 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 23.367900 27.969000 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 15.830600 18.210200 translate 0.035278 -0.035278 scale start_ol 3008 1168 moveto 3008 877 2906 648 conicto 2805 419 2612 260 conicto 2420 102 2139 19 conicto 1858 -64 1499 -64 conicto 1184 -64 888 -26 conicto 593 12 355 71 conicto 320 960 lineto 531 960 lineto 674 363 lineto 732 332 824 300 conicto 917 268 1023 244 conicto 1130 221 1243 206 conicto 1357 192 1453 192 conicto 1749 192 1939 266 conicto 2129 340 2239 474 conicto 2349 608 2390 793 conicto 2432 978 2432 1197 conicto 2432 1448 2362 1614 conicto 2293 1780 2171 1881 conicto 2050 1983 1887 2030 conicto 1725 2077 1539 2086 conicto 1088 2112 lineto 1088 2368 lineto 1541 2397 lineto 1898 2417 2069 2625 conicto 2240 2833 2240 3256 conicto 2240 3468 2196 3626 conicto 2153 3784 2060 3888 conicto 1968 3992 1818 4044 conicto 1669 4096 1455 4096 conicto 1358 4096 1260 4081 conicto 1163 4067 1073 4042 conicto 983 4018 906 3987 conicto 829 3956 772 3924 conicto 660 3392 lineto 448 3392 lineto 448 4215 lineto 559 4244 670 4269 conicto 782 4295 903 4312 conicto 1024 4330 1157 4341 conicto 1291 4352 1447 4352 conicto 2119 4352 2467 4091 conicto 2816 3830 2816 3289 conicto 2816 3086 2762 2910 conicto 2709 2735 2595 2600 conicto 2482 2465 2307 2373 conicto 2133 2281 1894 2246 conicto 2467 2179 2737 1912 conicto 3008 1645 3008 1168 conicto end_ol grestore gsave 46.287800 14.122900 translate 0.035278 -0.035278 scale start_ol 3008 765 moveto 3099 679 lineto 2759 226 2582 81 conicto 2406 -64 2184 -64 conicto 2021 -64 1949 21 conicto 1877 107 1877 291 conicto 1877 390 1981 785 conicto 2269 1869 lineto 2361 2225 2361 2369 conicto 2361 2560 2204 2560 conicto 1844 2560 1236 1625 conicto 1020 1290 915 1030 conicto 811 771 582 -5 conicto 92 -5 lineto 719 2295 lineto 732 2362 732 2407 conicto 732 2506 647 2542 conicto 562 2578 314 2578 conicto 314 2685 lineto 974 2804 1373 2880 conicto 1393 2867 lineto 955 1449 lineto 1458 2230 1801 2555 conicto 2145 2880 2459 2880 conicto 2648 2880 2769 2769 conicto 2890 2658 2890 2481 conicto 2890 2311 2831 2108 conicto 2459 762 lineto 2367 395 2367 350 conicto 2367 310 2400 277 conicto 2433 245 2472 245 conicto 2596 245 2871 594 conicto 3008 765 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 1.000000 srgb n 20.512792 33.856759 22.963829 22.963829 303.238951 339.960435 ellipse s 0.100000 slw [] 0 sd 0 slj 0 slc n 41.722173 25.704800 m 42.124613 26.092798 l 42.193547 25.538047 l s gsave 38.996100 19.563900 translate 0.035278 -0.035278 scale start_ol 2752 3008 moveto 2752 512 lineto 3660 374 lineto 3660 0 lineto 249 0 lineto 249 374 lineto 1088 512 lineto 1088 6592 lineto 180 6726 lineto 180 7104 lineto 3559 7104 lineto 4444 7104 5039 6958 conicto 5634 6813 5992 6550 conicto 6350 6288 6503 5922 conicto 6656 5557 6656 5117 conicto 6656 4783 6582 4481 conicto 6508 4179 6342 3924 conicto 6176 3670 5905 3474 conicto 5634 3278 5233 3156 conicto 7113 512 lineto 7872 374 lineto 7872 0 lineto 5580 0 lineto 3599 3008 lineto 2752 3008 lineto 4992 5107 moveto 4992 5532 4908 5806 conicto 4825 6081 4642 6240 conicto 4459 6400 4172 6464 conicto 3885 6528 3483 6528 conicto 2752 6528 lineto 2752 3584 lineto 3509 3584 lineto 3922 3584 4206 3669 conicto 4491 3754 4666 3938 conicto 4841 4122 4916 4409 conicto 4992 4697 4992 5107 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 37.029290 10.932322 m 42.609953 12.038833 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 42.180546 12.208559 m 42.719621 12.060578 l 42.277791 11.718107 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.500000 18.250000 m 24.046234 23.442798 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.830976 23.034312 m 24.036501 23.554177 l 24.329078 23.077838 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.930400 12.663800 m 19.602553 15.155279 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 19.848299 14.764376 m 19.501276 15.202640 l 20.060101 15.217299 l s gsave 39.380400 12.963800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 24.780400 20.738800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 22.430400 15.238800 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 25.330400 21.013800 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 23.005400 15.513800 translate 0.035278 -0.035278 scale start_ol 3008 1168 moveto 3008 877 2906 648 conicto 2805 419 2612 260 conicto 2420 102 2139 19 conicto 1858 -64 1499 -64 conicto 1184 -64 888 -26 conicto 593 12 355 71 conicto 320 960 lineto 531 960 lineto 674 363 lineto 732 332 824 300 conicto 917 268 1023 244 conicto 1130 221 1243 206 conicto 1357 192 1453 192 conicto 1749 192 1939 266 conicto 2129 340 2239 474 conicto 2349 608 2390 793 conicto 2432 978 2432 1197 conicto 2432 1448 2362 1614 conicto 2293 1780 2171 1881 conicto 2050 1983 1887 2030 conicto 1725 2077 1539 2086 conicto 1088 2112 lineto 1088 2368 lineto 1541 2397 lineto 1898 2417 2069 2625 conicto 2240 2833 2240 3256 conicto 2240 3468 2196 3626 conicto 2153 3784 2060 3888 conicto 1968 3992 1818 4044 conicto 1669 4096 1455 4096 conicto 1358 4096 1260 4081 conicto 1163 4067 1073 4042 conicto 983 4018 906 3987 conicto 829 3956 772 3924 conicto 660 3392 lineto 448 3392 lineto 448 4215 lineto 559 4244 670 4269 conicto 782 4295 903 4312 conicto 1024 4330 1157 4341 conicto 1291 4352 1447 4352 conicto 2119 4352 2467 4091 conicto 2816 3830 2816 3289 conicto 2816 3086 2762 2910 conicto 2709 2735 2595 2600 conicto 2482 2465 2307 2373 conicto 2133 2281 1894 2246 conicto 2467 2179 2737 1912 conicto 3008 1645 3008 1168 conicto end_ol grestore gsave 39.930400 13.213800 translate 0.035278 -0.035278 scale start_ol 3008 765 moveto 3099 679 lineto 2759 226 2582 81 conicto 2406 -64 2184 -64 conicto 2021 -64 1949 21 conicto 1877 107 1877 291 conicto 1877 390 1981 785 conicto 2269 1869 lineto 2361 2225 2361 2369 conicto 2361 2560 2204 2560 conicto 1844 2560 1236 1625 conicto 1020 1290 915 1030 conicto 811 771 582 -5 conicto 92 -5 lineto 719 2295 lineto 732 2362 732 2407 conicto 732 2506 647 2542 conicto 562 2578 314 2578 conicto 314 2685 lineto 974 2804 1373 2880 conicto 1393 2867 lineto 955 1449 lineto 1458 2230 1801 2555 conicto 2145 2880 2459 2880 conicto 2648 2880 2769 2769 conicto 2890 2658 2890 2481 conicto 2890 2311 2831 2108 conicto 2459 762 lineto 2367 395 2367 350 conicto 2367 310 2400 277 conicto 2433 245 2472 245 conicto 2596 245 2871 594 conicto 3008 765 lineto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 33.275200 24.442500 translate 0.035278 -0.035278 scale start_ol 3608 448 moveto 3662 448 3705 465 conicto 3748 482 3802 537 conicto 3856 593 3910 661 conicto 3964 729 4088 886 conicto 4213 1043 4342 1200 conicto 4494 1112 lineto 4029 384 3759 128 conicto 3489 -128 3176 -128 conicto 2917 -128 2787 25 conicto 2657 178 2549 604 conicto 2225 1916 lineto 1264 572 913 222 conicto 562 -128 248 -128 conicto 0 -128 -146 -3 conicto -292 121 -292 326 conicto -292 489 -184 596 conicto -76 704 76 704 conicto 205 704 410 593 conicto 616 483 702 483 conicto 886 483 1253 1015 conicto 2139 2313 lineto 1826 3657 lineto 1718 4149 1631 4280 conicto 1545 4411 1339 4411 conicto 1231 4411 735 4295 conicto 691 4453 lineto 810 4495 lineto 1761 4800 2074 4800 conicto 2290 4800 2403 4601 conicto 2517 4402 2636 3853 conicto 2755 3261 lineto 3316 4122 3672 4461 conicto 4029 4800 4386 4800 conicto 4580 4800 4704 4689 conicto 4828 4579 4828 4411 conicto 4828 4243 4725 4137 conicto 4623 4032 4450 4032 conicto 4342 4032 4169 4121 conicto 3997 4211 3900 4211 conicto 3586 4211 2841 2886 conicto 2841 2631 3273 902 conicto 3381 448 3608 448 conicto end_ol grestore gsave 34.022100 32.035100 translate 0.035278 -0.035278 scale start_ol 162 4530 moveto 1415 4777 1707 4800 conicto 1826 4800 2171 3779 conicto 2517 2759 2636 2040 conicto 2852 775 lineto 4170 2978 4170 3599 conicto 4170 3796 3878 3981 conicto 3586 4167 3586 4396 conicto 3586 4570 3705 4685 conicto 3824 4800 4008 4800 conicto 4256 4800 4429 4620 conicto 4602 4441 4602 4201 conicto 4602 3515 3802 1954 conicto 3003 393 1950 -923 conicto 897 -2240 292 -2240 conicto 54 -2240 -102 -2105 conicto -259 -1970 -259 -1765 conicto -259 -1592 -140 -1468 conicto -22 -1344 162 -1344 conicto 302 -1344 529 -1495 conicto 756 -1646 821 -1646 conicto 1080 -1646 1647 -940 conicto 2214 -234 2214 81 conicto 2214 223 2063 972 conicto 1912 1721 1772 2244 conicto 1404 3645 1182 4014 conicto 961 4384 497 4384 conicto 346 4384 162 4341 conicto 162 4530 lineto end_ol grestore gsave 43.017000 18.675800 translate 0.035278 -0.035278 scale start_ol 2906 -896 moveto 2484 -896 1712 -429 conicto 940 37 573 37 conicto 313 37 76 -158 conicto -22 -61 lineto 3327 3968 lineto 1750 3968 lineto 1372 3968 1210 3849 conicto 1048 3730 875 3329 conicto 702 3372 lineto 1037 4608 lineto 4105 4608 lineto 4105 4491 lineto 972 774 lineto 1458 666 1787 416 conicto 2117 167 2246 -66 conicto 2376 -299 2576 -483 conicto 2776 -667 3035 -667 conicto 3327 -667 3327 -505 conicto 3327 -461 3251 -298 conicto 3176 -136 3176 -17 conicto 3176 135 3278 227 conicto 3381 319 3543 319 conicto 3716 319 3818 211 conicto 3921 103 3921 -71 conicto 3921 -397 3613 -646 conicto 3305 -896 2906 -896 conicto end_ol grestore gsave 42.900000 28.250000 translate 0.035278 -0.035278 scale start_ol 551 4418 moveto 497 4418 459 4412 conicto 421 4407 389 4407 conicto 173 4407 lineto 173 4549 lineto 432 4592 454 4592 conicto 745 4634 950 4675 conicto 1156 4717 1237 4743 conicto 1318 4769 1382 4784 conicto 1447 4800 1512 4800 conicto 1707 4800 1863 3496 conicto 2020 2193 2052 1377 conicto 4126 4691 lineto 4191 4800 4266 4800 conicto 4342 4800 4353 4647 conicto 4699 811 lineto 5757 2137 6119 2713 conicto 6481 3289 6481 3637 conicto 6481 3800 6249 4028 conicto 6017 4257 6017 4431 conicto 6017 4800 6438 4800 conicto 6676 4800 6838 4642 conicto 7000 4484 7000 4234 conicto 7000 3712 6330 2614 conicto 5660 1516 4963 662 conicto 4267 -192 4126 -192 conicto 4072 -192 4045 -137 conicto 4018 -83 4008 135 conicto 3694 3611 lineto 2733 1912 lineto 2549 1584 2349 1202 conicto 2150 821 2031 603 conicto 1912 386 1798 184 conicto 1685 -18 1598 -105 conicto 1512 -192 1447 -192 conicto 1372 -192 1350 -94 conicto 1329 4 1307 321 conicto 1264 1279 lineto 1210 2794 972 3916 conicto 918 4200 831 4309 conicto 745 4418 551 4418 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.862745 0.945098 srgb n 42.454400 27.575000 m 31.199731 14.114345 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 31.640530 14.251797 m 31.128016 14.028572 l 31.256945 14.572518 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 31.150000 14.000000 m 24.646553 18.134713 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 24.840017 17.715466 m 24.552204 18.194698 l 25.108278 18.137409 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.150000 14.000000 m 25.072285 12.682462 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.504634 12.520380 m 24.963019 12.658775 l 25.398704 13.009030 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.100000 14.000000 m 36.901342 11.002640 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 36.671213 11.402937 m 37.000671 10.951320 l 36.441703 10.958724 l s gsave 26.795000 17.935000 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 27.495000 18.260000 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore gsave 26.495000 14.335000 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 27.145000 14.660000 translate 0.035278 -0.035278 scale start_ol 3008 1168 moveto 3008 877 2906 648 conicto 2805 419 2612 260 conicto 2420 102 2139 19 conicto 1858 -64 1499 -64 conicto 1184 -64 888 -26 conicto 593 12 355 71 conicto 320 960 lineto 531 960 lineto 674 363 lineto 732 332 824 300 conicto 917 268 1023 244 conicto 1130 221 1243 206 conicto 1357 192 1453 192 conicto 1749 192 1939 266 conicto 2129 340 2239 474 conicto 2349 608 2390 793 conicto 2432 978 2432 1197 conicto 2432 1448 2362 1614 conicto 2293 1780 2171 1881 conicto 2050 1983 1887 2030 conicto 1725 2077 1539 2086 conicto 1088 2112 lineto 1088 2368 lineto 1541 2397 lineto 1898 2417 2069 2625 conicto 2240 2833 2240 3256 conicto 2240 3468 2196 3626 conicto 2153 3784 2060 3888 conicto 1968 3992 1818 4044 conicto 1669 4096 1455 4096 conicto 1358 4096 1260 4081 conicto 1163 4067 1073 4042 conicto 983 4018 906 3987 conicto 829 3956 772 3924 conicto 660 3392 lineto 448 3392 lineto 448 4215 lineto 559 4244 670 4269 conicto 782 4295 903 4312 conicto 1024 4330 1157 4341 conicto 1291 4352 1447 4352 conicto 2119 4352 2467 4091 conicto 2816 3830 2816 3289 conicto 2816 3086 2762 2910 conicto 2709 2735 2595 2600 conicto 2482 2465 2307 2373 conicto 2133 2281 1894 2246 conicto 2467 2179 2737 1912 conicto 3008 1645 3008 1168 conicto end_ol grestore gsave 34.490000 13.450000 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 35.090000 13.775000 translate 0.035278 -0.035278 scale start_ol 3008 765 moveto 3099 679 lineto 2759 226 2582 81 conicto 2406 -64 2184 -64 conicto 2021 -64 1949 21 conicto 1877 107 1877 291 conicto 1877 390 1981 785 conicto 2269 1869 lineto 2361 2225 2361 2369 conicto 2361 2560 2204 2560 conicto 1844 2560 1236 1625 conicto 1020 1290 915 1030 conicto 811 771 582 -5 conicto 92 -5 lineto 719 2295 lineto 732 2362 732 2407 conicto 732 2506 647 2542 conicto 562 2578 314 2578 conicto 314 2685 lineto 974 2804 1373 2880 conicto 1393 2867 lineto 955 1449 lineto 1458 2230 1801 2555 conicto 2145 2880 2459 2880 conicto 2648 2880 2769 2769 conicto 2890 2658 2890 2481 conicto 2890 2311 2831 2108 conicto 2459 762 lineto 2367 395 2367 350 conicto 2367 310 2400 277 conicto 2433 245 2472 245 conicto 2596 245 2871 594 conicto 3008 765 lineto end_ol grestore 0.000000 0.862745 0.945098 srgb gsave 39.041800 18.250000 translate 0.035278 -0.035278 scale start_ol 5568 2752 moveto 5568 2240 lineto 512 2240 lineto 512 2752 lineto 5568 2752 lineto 5568 4928 moveto 5568 4416 lineto 512 4416 lineto 512 4928 lineto 5568 4928 lineto end_ol grestore gsave 39.848539 18.250000 translate 0.035278 -0.035278 scale start_ol 2432 1856 moveto 1984 1856 lineto 1847 3648 lineto 2626 3800 lineto 2822 3836 2985 3927 conicto 3149 4019 3269 4194 conicto 3389 4369 3454 4643 conicto 3520 4918 3520 5320 conicto 3520 5701 3451 5967 conicto 3382 6234 3228 6401 conicto 3074 6568 2821 6644 conicto 2568 6720 2199 6720 conicto 1869 6720 1596 6648 conicto 1324 6577 1132 6470 conicto 939 5632 lineto 576 5632 lineto 576 6946 lineto 956 7044 1339 7106 conicto 1722 7168 2178 7168 conicto 3329 7168 3904 6718 conicto 4480 6268 4480 5389 conicto 4480 5022 4392 4690 conicto 4304 4358 4104 4088 conicto 3905 3819 3585 3622 conicto 3266 3426 2803 3332 conicto 2500 3264 lineto 2432 1856 lineto 2880 512 moveto 2880 380 2829 263 conicto 2779 147 2694 59 conicto 2609 -28 2492 -78 conicto 2375 -128 2243 -128 conicto 2105 -128 1988 -78 conicto 1871 -28 1786 59 conicto 1701 147 1650 263 conicto 1600 380 1600 512 conicto 1600 644 1650 763 conicto 1701 882 1786 967 conicto 1871 1052 1988 1102 conicto 2105 1152 2243 1152 conicto 2375 1152 2492 1102 conicto 2609 1052 2694 967 conicto 2779 882 2829 763 conicto 2880 644 2880 512 conicto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 40.964100 19.570000 translate 0.035278 -0.035278 scale start_ol 5568 2752 moveto 5568 2240 lineto 512 2240 lineto 512 2752 lineto 5568 2752 lineto 5568 4928 moveto 5568 4416 lineto 512 4416 lineto 512 4928 lineto 5568 4928 lineto end_ol grestore gsave 41.770839 19.570000 translate 0.035278 -0.035278 scale start_ol 2432 1856 moveto 1984 1856 lineto 1847 3648 lineto 2626 3800 lineto 2822 3836 2985 3927 conicto 3149 4019 3269 4194 conicto 3389 4369 3454 4643 conicto 3520 4918 3520 5320 conicto 3520 5701 3451 5967 conicto 3382 6234 3228 6401 conicto 3074 6568 2821 6644 conicto 2568 6720 2199 6720 conicto 1869 6720 1596 6648 conicto 1324 6577 1132 6470 conicto 939 5632 lineto 576 5632 lineto 576 6946 lineto 956 7044 1339 7106 conicto 1722 7168 2178 7168 conicto 3329 7168 3904 6718 conicto 4480 6268 4480 5389 conicto 4480 5022 4392 4690 conicto 4304 4358 4104 4088 conicto 3905 3819 3585 3622 conicto 3266 3426 2803 3332 conicto 2500 3264 lineto 2432 1856 lineto 2880 512 moveto 2880 380 2829 263 conicto 2779 147 2694 59 conicto 2609 -28 2492 -78 conicto 2375 -128 2243 -128 conicto 2105 -128 1988 -78 conicto 1871 -28 1786 59 conicto 1701 147 1650 263 conicto 1600 380 1600 512 conicto 1600 644 1650 763 conicto 1701 882 1786 967 conicto 1871 1052 1988 1102 conicto 2105 1152 2243 1152 conicto 2375 1152 2492 1102 conicto 2609 1052 2694 967 conicto 2779 882 2829 763 conicto 2880 644 2880 512 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 31.100000 13.950000 m 28.756900 19.512728 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 28.677196 19.057927 m 28.713500 19.615764 l 29.137987 19.252019 l s gsave 30.015100 18.753800 translate 0.035278 -0.035278 scale start_ol 5056 4565 moveto 3073 -128 lineto 2424 -128 lineto 320 4544 lineto 0 4663 lineto 0 4992 lineto 2519 4992 lineto 2519 4663 lineto 1928 4534 lineto 3232 1626 lineto 4375 4544 lineto 3794 4663 lineto 3794 4992 lineto 5440 4992 lineto 5440 4664 lineto 5056 4565 lineto end_ol grestore gsave 30.715100 19.078800 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 28.694635 19.653900 m 29.984334 25.182240 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.652678 24.860992 m 30.009735 25.291120 l 30.139603 24.747398 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.000000 0.000000 0.000000 srgb n 30.622500 27.912500 0.212500 0.212500 0 360 ellipse f n 30.622500 27.912500 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 30.622500 27.912500 0.212500 0.212500 0 360 ellipse cp s gsave 29.325000 29.213200 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 30.187500 29.508200 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 1.000000 0.000000 0.000000 srgb gsave 29.575000 21.825000 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 30.125000 22.100000 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 31.091100 13.902000 m 29.911981 9.814845 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 30.259789 10.118533 m 29.880991 9.707422 l 29.779381 10.257127 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 31.135200 13.971900 m 32.563144 12.126834 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 32.523258 12.586840 m 32.631572 12.038417 l 32.127845 12.280820 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.150000 14.000000 m 30.838100 16.058417 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 30.649078 15.637148 m 30.821350 16.168958 l 31.143435 15.712055 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 31.250000 14.000000 m 28.954671 12.990055 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.410678 12.917568 m 28.852335 12.945028 l 29.209308 13.375226 l s gsave 31.937900 14.440600 translate 0.035278 -0.035278 scale start_ol 4051 3625 moveto 4051 3767 3824 3984 conicto 3597 4201 3597 4430 conicto 3597 4604 3705 4702 conicto 3813 4800 3997 4800 conicto 4245 4800 4423 4609 conicto 4602 4419 4602 4159 conicto 4602 3854 4413 3381 conicto 4224 2908 3943 2505 conicto 3111 1331 2441 569 conicto 1772 -192 1566 -192 conicto 1469 -192 1469 189 conicto 1469 656 1393 1651 conicto 1318 2647 1231 3212 conicto 1123 3962 993 4179 conicto 864 4397 551 4397 conicto 346 4397 227 4386 conicto 227 4528 lineto 605 4593 886 4647 conicto 1167 4702 1275 4734 conicto 1383 4767 1469 4783 conicto 1555 4800 1642 4800 conicto 1815 4800 1993 3516 conicto 2171 2233 2236 765 conicto 2571 1113 lineto 3143 1722 3597 2488 conicto 4051 3255 4051 3625 conicto end_ol grestore gsave 32.529839 14.440600 translate 0.035278 -0.035278 scale start_ol 961 4414 moveto 605 4414 lineto 583 4570 lineto 2247 4800 2268 4800 conicto 2322 4800 2322 4758 conicto 1977 3589 lineto 2452 4243 2873 4521 conicto 3295 4800 3824 4800 conicto 4396 4800 4731 4434 conicto 5066 4069 5066 3437 conicto 5066 2140 4034 1006 conicto 3003 -128 1826 -128 conicto 1469 -128 1113 77 conicto 713 -1429 713 -1747 conicto 713 -2077 1404 -2077 conicto 1404 -2240 lineto -810 -2240 lineto -810 -2066 lineto -670 -2066 -583 -2049 conicto -497 -2033 -410 -1983 conicto -324 -1934 -281 -1874 conicto -238 -1815 -173 -1678 conicto -108 -1542 -70 -1405 conicto -32 -1269 32 -1006 conicto 97 -744 156 -487 conicto 216 -231 324 190 conicto 432 611 540 1026 conicto 1307 3955 1307 4119 conicto 1307 4217 1188 4315 conicto 1069 4414 961 4414 conicto 4094 3415 moveto 4094 4352 3381 4352 conicto 2981 4352 2576 3997 conicto 2171 3643 1966 3109 conicto 1728 2498 1496 1637 conicto 1264 777 1264 505 conicto 1264 330 1409 215 conicto 1555 101 1782 101 conicto 2430 101 2986 690 conicto 3543 1279 3818 2030 conicto 4094 2782 4094 3415 conicto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 40.100000 19.800000 translate 0.035278 -0.035278 scale start_ol 2452 2172 moveto 2452 2257 2314 2388 conicto 2177 2520 2177 2657 conicto 2177 2762 2242 2821 conicto 2308 2880 2419 2880 conicto 2570 2880 2678 2765 conicto 2786 2650 2786 2493 conicto 2786 2310 2671 2024 conicto 2557 1739 2387 1497 conicto 1883 790 1477 331 conicto 1072 -128 948 -128 conicto 889 -128 889 102 conicto 889 384 843 983 conicto 798 1583 745 1923 conicto 680 2375 601 2506 conicto 523 2637 333 2637 conicto 209 2637 137 2630 conicto 137 2716 lineto 366 2756 536 2788 conicto 706 2821 771 2840 conicto 837 2860 889 2870 conicto 942 2880 994 2880 conicto 1099 2880 1206 2107 conicto 1314 1334 1354 449 conicto 1556 659 lineto 1903 1026 2177 1487 conicto 2452 1949 2452 2172 conicto end_ol grestore gsave 40.459660 19.800000 translate 0.035278 -0.035278 scale start_ol 582 2660 moveto 366 2660 lineto 353 2749 lineto 1360 2880 1373 2880 conicto 1406 2880 1406 2856 conicto 1197 2164 lineto 1484 2550 1739 2715 conicto 1994 2880 2315 2880 conicto 2661 2880 2864 2661 conicto 3067 2443 3067 2065 conicto 3067 1290 2442 613 conicto 1818 -64 1105 -64 conicto 889 -64 674 47 conicto 432 -829 432 -1015 conicto 432 -1207 850 -1207 conicto 850 -1344 lineto -490 -1344 lineto -490 -1207 lineto -405 -1207 -353 -1197 conicto -301 -1188 -248 -1158 conicto -196 -1129 -170 -1093 conicto -144 -1057 -104 -975 conicto -65 -894 -42 -812 conicto -20 -731 19 -574 conicto 59 -418 95 -264 conicto 131 -111 196 140 conicto 262 391 327 639 conicto 791 2386 791 2484 conicto 791 2543 719 2601 conicto 647 2660 582 2660 conicto 2478 2058 moveto 2478 2624 2047 2624 conicto 1805 2624 1559 2410 conicto 1314 2196 1190 1875 conicto 1046 1507 905 987 conicto 765 468 765 304 conicto 765 198 853 129 conicto 942 60 1079 60 conicto 1471 60 1808 415 conicto 2145 770 2311 1224 conicto 2478 1678 2478 2058 conicto end_ol grestore 0.000000 0.862745 0.945098 srgb gsave 38.150000 18.500000 translate 0.035278 -0.035278 scale start_ol 2452 2172 moveto 2452 2257 2314 2388 conicto 2177 2520 2177 2657 conicto 2177 2762 2242 2821 conicto 2308 2880 2419 2880 conicto 2570 2880 2678 2765 conicto 2786 2650 2786 2493 conicto 2786 2310 2671 2024 conicto 2557 1739 2387 1497 conicto 1883 790 1477 331 conicto 1072 -128 948 -128 conicto 889 -128 889 102 conicto 889 384 843 983 conicto 798 1583 745 1923 conicto 680 2375 601 2506 conicto 523 2637 333 2637 conicto 209 2637 137 2630 conicto 137 2716 lineto 366 2756 536 2788 conicto 706 2821 771 2840 conicto 837 2860 889 2870 conicto 942 2880 994 2880 conicto 1099 2880 1206 2107 conicto 1314 1334 1354 449 conicto 1556 659 lineto 1903 1026 2177 1487 conicto 2452 1949 2452 2172 conicto end_ol grestore gsave 38.509660 18.500000 translate 0.035278 -0.035278 scale start_ol 582 2660 moveto 366 2660 lineto 353 2749 lineto 1360 2880 1373 2880 conicto 1406 2880 1406 2856 conicto 1197 2164 lineto 1484 2550 1739 2715 conicto 1994 2880 2315 2880 conicto 2661 2880 2864 2661 conicto 3067 2443 3067 2065 conicto 3067 1290 2442 613 conicto 1818 -64 1105 -64 conicto 889 -64 674 47 conicto 432 -829 432 -1015 conicto 432 -1207 850 -1207 conicto 850 -1344 lineto -490 -1344 lineto -490 -1207 lineto -405 -1207 -353 -1197 conicto -301 -1188 -248 -1158 conicto -196 -1129 -170 -1093 conicto -144 -1057 -104 -975 conicto -65 -894 -42 -812 conicto -20 -731 19 -574 conicto 59 -418 95 -264 conicto 131 -111 196 140 conicto 262 391 327 639 conicto 791 2386 791 2484 conicto 791 2543 719 2601 conicto 647 2660 582 2660 conicto 2478 2058 moveto 2478 2624 2047 2624 conicto 1805 2624 1559 2410 conicto 1314 2196 1190 1875 conicto 1046 1507 905 987 conicto 765 468 765 304 conicto 765 198 853 129 conicto 942 60 1079 60 conicto 1471 60 1808 415 conicto 2145 770 2311 1224 conicto 2478 1678 2478 2058 conicto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 29.860200 9.705170 m 25.912767 7.854816 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 26.370371 7.793215 m 25.811533 7.807363 l 26.158155 8.245944 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 24.932910 12.619168 m 24.782162 11.145190 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 25.070360 11.505937 m 24.770787 11.033967 l 24.572955 11.556808 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.932395 12.635931 m 23.594745 12.704165 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.969701 12.434713 m 23.483086 12.709860 l 23.995173 12.934064 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.943810 12.649354 m 24.934705 13.783552 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 24.687829 13.393361 m 24.933807 13.895352 l 25.187813 13.397375 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.533883 18.204152 m 25.330749 19.174246 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 24.891163 19.032962 m 25.401715 19.260639 l 25.277526 18.715592 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.517489 18.185571 m 23.160902 18.606109 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 23.457667 18.252376 m 23.054112 18.639214 l 23.605715 18.729955 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 24.546840 18.179272 m 24.547288 16.756117 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 24.797166 17.144393 m 24.547323 16.644314 l 24.297166 17.144235 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 28.671737 19.661709 m 27.488738 19.130228 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 27.945292 19.061271 m 27.386754 19.084410 l 27.740388 19.517357 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 28.673477 19.675764 m 27.506608 20.491259 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 27.681589 20.063967 m 27.414967 20.555305 l 27.968010 20.473800 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 28.722708 19.649916 m 29.480957 20.634937 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 29.046060 20.479821 m 29.549156 20.723532 l 29.442267 20.174829 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 37.028569 10.937164 m 38.225663 10.745959 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 37.881757 11.054058 m 38.336067 10.728325 l 37.802895 10.560316 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 36.990014 10.917886 m 36.867357 12.223044 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 36.654776 11.813159 m 36.856896 12.334357 l 37.152582 11.859942 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 37.000655 10.942021 m 36.194892 10.136258 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 36.646165 10.233978 m 36.115835 10.057201 l 36.292611 10.587531 l s showpage opengv/doc/addons/images/triangulation_central.png0000664016516101651610000005605713344612246021404 0ustar dimadima‰PNG  IHDRÐHo 8ybKGDÿÿÿ ½§“ IDATxœìÝwXSgð“„™ KE.”ªu⮻ܭÜ8pà¨Xq"î…V¨£ŽŠTêl-âDÜ([ÊH @ȾßáCD@À›ÜÎïáù¾äæÞ÷¥^Î} @!¤|tª@¡Ê­^½šF£mܸ‘ê@HCÃ.BH=•””…B===]]]ªc!&\„R,) „ÔÔÒ¥K9Α#G¨„4˜pBjª  €ÇãÉårª! –BjJ ˆD"‹Åd2©Ž…˜pBHE°¤€RS“'Oæp8—/_¦:Ò`ÂE©)Çãñ¨Ž‚LXR@©©¢¢"‰Db`` ­­Mu,µ–™™™••åîî^þ &\„"ÙÝ»wûôéãààðìÙ3:ýS!K !5åååÅápîß¿Ou 5•½aéTÚ¡C‡Æ»ººòùüò'hQBUËåòx¼ò=D5×·oßgÏžÙÚÚNž<ùùóçzzzN¨7„PCsýúu.—Û¾}{ª©—Ë]¾|yhh(,X°`À€mÛ¶€/³-` !„¾Exxøøñãíììµ´¾R3À.BHMµoßžÃᤤ¤PHEb±xÓ¦MíÛ· …cÇŽ1cÆï¿ÿþÕl ØÃE©-[[Û÷ïß¿{÷®I“&TÇRª¸¸XKKKGG§}ûöqqqgÏž5jTÍ/Ç„‹"_ddä;w?~üîÝ;Åümmm6›íììÜ£Gooo;;»¯6RPP —ËÕä¹YXXØ‚ üüü/^|ç΂ ºwï^«0á"„Èçè蘔”t:ÝÖÖ–Åb%&&ŠÅbŧ:::þþþ«W¯¦4Æš‰D/^¼pwwŠŠòòò9rä¹sçêÖ”ZüÜ@i¤É“'ggg§¤¤¼|ù2''gÊ”)Šãb±xÍš56l¨þr‡#”hÕ>|øàäääååUXXØ¿ÿ»wïÖ9ÛöpBÊ èá>zô¨üÜV‰Dâä䔚šªxËd2SSS---«jDGGG"‘ˆÅbÕOí•H$ÇŽ3fŒ‰‰I= ÃÂÂZ¶lùÍb!¤úúúmÚ´)D[[{РAeoE"Qddd5-|üø‘ËåR²ÂŒ3fΜ¹cǸxñâãÇ¿=ÛÎ4C)C³fÍ:wîüåH)‡òouÞª°Ùlò#«šL&;yò$—Ë]´hÑìÙ³Ÿ>}ªèž“&\„ù¢¢¢*=®££Sþ­H$ªª…¢¢"[[[ƒwïÞ‘\âââ¦Nª¯¯?qâÄ.]ºÄÅÅ‘~ ,) ¤™–,YBûBXXؤI“\\\Œµµµ5jÔµk×ÀÀÀ¢¢¢ —ÿ÷ß_^^½G}5ª?–kccSÕ™"‘ˆÇã©à‰Yxx¸››[ff¦»»û¬Y³BBBLMM•u3!¤‰’““wíÚeeeUþß;Fóðð˜:uêìÙ³ÍÌÌÊŽÛØØ¼|ù²üåwîÜ©m2yøðáW£êÒ¥KùKžüüùóTGT9¬á"Ôpåææ–ŸÔÛ¬Y3Ò³mqqñ²eË:tè0bĈçÏŸ×üÂK—.q8œò%*•žžþã?*ºÏK—.]²dɾ)beÂ’B ×ýû÷Ë¿ýá‡H¿ÅäÉ“ÿøãxüøñÍ›7_½zÕ¸qãš\X\\Ìãñª©)¿ÿ¾I“&úúúW¯^•H$iiivvv[·n%-t%À.B ׉'Ê^3™Ì™3g’Û>ŸÏWd[…‚‚‚³gÏÖðÚQ£Fq¹ÜƒVúéüùóíííoÞ¼Éf³ÃÂÂk²Iå0á"Ô€$''K$Åë#GŽ”Oëׯwtt$÷v_öOk>ê@GG‡ÍfWÅ•””ôìÙ3hܸ±––Ö«W¯`àÀÖèQ_ªœGŒR± k)€–––™™YùEµµ´´6lØ ¤<==Ën¤££óúõë^xðàA6›½téÒ²#‘‘‘ZZZA¾{÷N)+öpj@ÆŽÛ¶m[¹\^TTdddäìììããóôéS%ÝñôéÓ?üðƒ‘‘QëÖ­/^¼Xój y<žL&ËÌÌÜ´iA={ö´²²jÞ¼¹@ 000hÒ¤‰’bV†&«0,¬&‹¨ ¡PXRR¢££Ó¦M›¤¤¤ .üðÃ%%%¦ÆÕ/ØÃE¨QÆD2eÈÎÎ^¾|ùÍ›7õõõ—-[6qâDgggøb"r½ƒ ¡¤ì‰™Ú’Édpþüù]»v;6((èçŸ>yòd‹-¨˜pj@Ô¹„(üüüÚµk'•J§M›æêê*“Éär9Õq‘ '> „(ÆçóY,–ŽŽÎ… nܸѿÿ…Âú^C¨{¸!*:t¨iÓ¦Ç×ÒÒÚ»wï½{÷ú÷ïzzzl6[WW—êÉ„ !ÍôüùóeË–)¦”Y½zõ¦M›bcc©ŠªLQQÑ“'OÀÄÄ„ÇãÅÄÄ@Ÿ>}:wî¬8Á××—Ã᜿OŸ>OŸ>7nœâõŸþ™““sñâÅ={ö\¼x177·ü…<ÇãÑh4ª"W,) „HFÄñãÇwìØqûöm‡ãããÓ«W¯aÆ)²'AóçÏ ÑÒÒb2™ÅÅÅŠ«Ølöž={Ưx[XX(•J k²§z} !D‰D"‰ úöí{ýúõ   Jw¢$bðàÁ‘‘‘ŽÓh´3gÎŒ5J%ÁRK !rܺu«U«V°iÓ¦ÐÐÐ Tuòëׯ¿mÔ¨±Ùì¯æîú.B¨Öüýý‡ºyóf yóæM×®]k~y‹-¬­­+ýÈØØØÉÉ \]]9Nff&)« L¸¡šº}ûvPPL™2ÅÚÚZ±(¸™™YmgßÒéôÀÀÀJ?*((X±bäääðxŸ¯I«…a !TQRR’——׸qã`õêÕ¿üòËÎ;Uvw//¯?þøD"Ñ’%KTv_À.Bè“÷ïß7iÒ$33ÓÑÑQ[[;11ÑÌÌŒ’H®^½:iÒ¤ß~û­_¿~”  ˜pB¥&Ož|êÔ©{÷îuèÐáÏ?ÿìÚµ«bH,Uø|¾‘‘…K 5t¯_¿V¬l`eeÅd2+Õ:”Âl›——ÇápÜÝÝ© @I°‡‹PƒvæÌ™qãÆõìÙóÆ<O$YZZRdffZ[[7nÜ8##ƒêXÈ„=\„¢7oÞ(æ‰õë×ÏÜÜÜÍÍM"‘°Ùluȶ`iiÉår+l9¬°‡‹Pƒ#‹mmm?~üxóæÍï¿ÿ^1ü‹ê ìá"ÔPdddÌš5ëï¿ÿÖÑÑñóó›6mZÓ¦M@ ³íëׯ9N·nݨ„d5O!T)Å4ܰ°°<{ö¬_¿~ .¤:¨ê”””ðx<¡PHu $Ã’BšŒÏç¯^½úÞ½{÷îÝ …~~~óæÍS,ǥΤRiaa¡––YsˆÕ&\„4SVV–¹¹¹D"iÖ¬YVVVtt´‡‡ÕA5tXÃEHmÛ¶ÍÑÑñôéÓºººŒ­_ÙöŸþáp8ǧ:’aÂEHsäçç?{ö ŒKJJ>|ƒ jÛ¶-Õ¡ÕŽ@ P ¦:’aI! ñôéÓ=z˜››¿zõŠ ˆ§OŸvèÐê êH"‘ikkP ™°‡‹PýÆçówîÜ)‘H\]]---¹\®¶¶výͶ ­­Íf³5,Û&\„ê»Áƒ/\¸ððáà ãÞ½{‘‘‘æææTõ­Îž=ËápfΜIu $Ãq¸Õ?………{÷îµ²²š4i’¯¯oYÖÄÄ„êÐÈQTTÄãñ$ Õ k¸Õ?W®\ŸÏãñd2Õ k¸©#‰D¢H{óæÍÞ½{{zzÞ¹s‡ê TG(–””èêêêééQ ™0á"¤vx<^ÇŽ³³³SRRLMM###½¼¼ètü}´ÞÃo!BêB.—Ÿ;w.77—Íf7kÖÌÊÊêÝ»w0pàÀ†–m׬YÃáp‚ƒƒ©„d 뻈:óññ=zt`` œ8qâåË—íÚµ£:(j(j¸r¹œê@H†%„¨DÄÅ‹ÓÓÓçÏŸ;jÔ¨7Ž?žê¸(&D"‹Åb2™TÇB&L¸Q)>>ÞÅÅ…Éd&%%YYY)¶f :(¤,XR@ˆ·nÝêÙ³ç»wïZ¶léãã³yófcccÀl«0kÖ,‡sæÌª!&\„TJ±O×áÇÿùçŸ;vÀŽ;|}}5oVÕ·ÈÏÏçñxš÷û7–R‘W¯^Í™3§iÓ¦ÇOLLüóÏ?gΜ©¯¯Ou\꨸¸X,ëëëëèèP ™0á"¤t¯_¿vvvNNNnÙ²%‡ÃIHHа½Q aI!%"bÈ!®®®/_¾tppˆˆˆHLLÄlûU#FŒàp8·oߦ:’aÂEH)ž>}š””D£Ñlllôõõ_¿~ ýúõÓ¼] ”Ëåòx<Fu $Ã’Bä;|øðÏ?ÿüÃ?œ?>''‡F£5jÔˆê ê“ÂÂB©Tjhh¨¥¥Q›$`!Ò<þ\±¬×àÁƒMMM[¶l)—ËÍÌÌ0ÛÖ–¡¡!›ÍÖ°l ØÃEˆ,EEEÖÖÖ|>?&&¦K—.B¡PSWWnݺ½~ýú¿ÿþkÕªÕ± {¸}“W¯^Mœ8ñîÝ»K–,Y¸pa³fͳí·ÈËËãñxš7 {¸Õ‘bî† Ö¬Yãååõ×_Q‘æ(((Ë寯ƶLš¦•HR¼¼¼U«V%$$ܸqÃ××777wÁ‚T¥Q5öpª…ŒŒ kkëÂÂB‡üüü§OŸjX‘QM4oÞŸÏb±0Ûª€L&ãp8fffTB>¥€P%zõêõôéS33³ñãÇ?{öÌÄĄꈱXÌãñ4lƒtìá"TŠÇãœ={|||èêê ˜mULWW—ËåfffRù°†‹P©°°° &888¼}ûVóæ8!u€=\Ô I$’;vtêÔI"‘Œ;vÆŒaaa˜m©•™™Éáp\\\¨„|ØÃE ”@ `0ZZZmÚ´yùòåÙ³gGEuP %%ÅÁÁÁÞÞ>99™êXH†=\Ô;wÎÑÑñÀ #$$äï¿ÿÆl«>ììì¸\î“'O¨„|˜pQ"‰S˜LfVVÖ7 G}ûö¥:4ô Ng³Ù¹œ–PC‘™™éááQRR’œœl``pçÎï¾ûŽê P%âââzõêÕ¦M›[·nQ ɰ‡‹4œD"9xð`~~~ãÆ7nlnnžžž˜mÕ–P(äñxB¡ê@ȇ=\¤á&L˜¶víÚuëÖeeeYXXhØ«šG*•jiiiÞöÆø_Ò@2™,<<üàÁƒðÓO?999)¦äZYYa¶UZZZl6[ó²-`i¤‡vêÔÉÐÐ099¹Q£FŠ­¨ ÕÔµkׯŽÛ·oßÓ§OS Éð§=ÒgÏžíÖ­[NNNÇŽgΜ¹gÏ6› ˜më—ââb'‹©„|ØÃEš@±EîðáÃ/^¼¨(×Rª;±X\\\¬£££¯¯Ou,$Ä‹ê·ØØØ¹sçvêÔi×®]ÏŸ?ÿ÷ß§OŸŽ;æ"õ„%T_½~ý´µµÒÓÓÇŽ;bÄXºtéÒ¥K÷îÝKuPˆË—/çp8е‡4 öpõ222¬­­Y,VTTTIIÉ»wïlmmýõWªãBÔ(((àñxr¹œê@ȇ5\D±%K–ìÞ½ûæÍ›žžžW®\iݺµ­­-ÕA!* ‘HÄb±˜L&Õ± K ˆiiiÏŸ?###xøð! 4³-b±Xl6[ó²-`ÂE”ˆŠŠrrrš={6,Z´èíÛ· .¤:(¤.¦M›Æáp.^¼Hu äÄ‹T'##cÓ¦MAtíÚÕØØØÖÖV 4mÚ”êÐáñx<ê(”k¸HEär¹££cJJÊ¥K—†šŸŸobbBuPHI$mmmªc!—jFJ•““³iÓ&‘HäääD‹Å3fL£F4oL;"‹ŽŽŽžžžFîÓ=\¤\ûöí›3gŽ››[\\F£:T 4(&&&""¢k×®TÇB2¬á"ò ‚Õ«WwíÚU&“MŸ>}Ê”)¡¡¡˜mQ q¹\§‘û+c‘©°°P1)ÓÙÙ9))éÚµk½{÷¦:(TÏJ¥RCCC--M›™¥?CUNœ8ѬY³S§NiiiíÝ»÷Þ½{˜mQ²ÙlÍ˶€ —ññàë nn`d4èꂳ3|üHuXu$ž>} t:=''çÆзoßN:Qª—:vìÈáp’’’¨„|ø3DÝâEP¶_‹ÄÇCI ¥aÕQbbb÷îݵµµÆoooß­[7ªƒBõ[nn.ÇÓÈQ ØÃU­¿þ_ßOÙv÷n(.†Í›)©.„BáÞ½{KJJÌÍÍ­­­³²²èt:f[ôíâââ¸\®FNòƇfªÕ±#ÿ³·õ![qòäIOOÏ‚‚‚>}úLš4)$$ÄÀÀ€F£a¶EJ’™™Éår5/Û&\•ªW+ØËår‘HD£ÑŽ?}ôèQ ;v,ÎCJÅf³5uÃP,)¨Dx8„†Â?ÿ€PXù jö]¸}ûö¼yóFŒ±~ýúû÷ï¿}ûv„ Ø¥E* lllôôô222¨Ž…|øÐL%®]ƒÔThÔÒÓ?Ô×êbªAñññÎÎÎ,ëåË—°nݺÎ;wîÜ™êÐPC!‹y<ž¦v±‡«BW¯Â€ŸÞÔES‘@ èի׋/’““ÍÍͯ\¹Ò·o_ªãB Aùùù4M#—KÆ_\½z533“ÅbYZZ¿yó „Ù©Fc³Ù&T¢˜pºÕ«W0`óæÍpðàÁäääï¾ûŽê PÕšš:ÎÐ0ÚÍê@”nuóæÍmÛ¶À¸qãlllœœœÀÜÜ\#·JEõˆH(\RTԕχׯ©Ž…|øÐ¬!JKKëׯN>|x«V­RSS5r¡T5‹+ínÝ GR 鰇ۀܽ{·wïÞoÞ¼±³³›5k–¿¿¿™™`¶EêB"¡¯YSúúÔ©ÏFõhL¸ ‚L&€ãÇß¼yó×_€={ö¬Y³Fóæª£úíÀHH(}-ÃÖ­”FC>L¸.))é‡~ðöö€U«V­\¹RQºEHíÂúõŸ9|rr(ŠF)°†[ßdgÃÅ‹59‘—“ÃÖÒ2qpˆŠŠb2™yyyvvv›6mRv€ÕÑŽÓ«@!!°n5ñ(&ÜúÆÜ8˜1¾6P‘ 555}ñâôéÓ]»v555UM€ÕEvvå„à`X² TR`I¡5 bc¡cÇêÏ’\óöKË¡C‡6jÔH5¡!TGAAPTTÉq.BCU²`­Ÿàî]X»¶š5‹-°c‡*ƒB¨ŽÒÓaÏž*?ݶíÓ®Tõ&ÜzKK Ö­ƒ?þ X¬J>íÚÕp˕DŽP¬[÷iÓ==€ò{¤§¤À™3D¥˜pUB.‡³gáÈ‘Ï>ë×Ù3›[—6e2 %-¢ ?b³!,ì³ÿdR[¯_— 5‚µkáɈ‰ï¿/=ç×_Õm Ó:" U~…‡×®5‰„·eKžâò,+«ó̘ IDATbO­ÑhDd¤rþ)Á°aDÓ¦ÄîÝDQAáAA@¾Aé§ÿMtè@TIì᪄D•_?þXÓv¤R8xš77ñóã¥ééÁ™3–éé¬ò#æÌùlH„ÔYVŒ 0>è뀰 ¤e³ûö…àÜ9¸pÂ0É‚ëáÖ2YÉáÃ…+Wšs¹ wtÜocÓ38¸•«+€ (–ÇïÒþý´µ)¡ºÅÅ1Ûµ#Z¶¤UX¼F&:êùöNXæS{Qª¿u«Þ«Wz‰ôµküýç”/Ñ*Æ*èëÃñã˜mQ½¦X­Žöå’±â&\5Fpî\ž¯¯iV€½}Ü?Ð'Lpsw¯x¦"áîÝ -Z¨:H„HuâСIY\®Õ‘(&\5UrâmÓ&Ý·oM2îöí;*"¢mU[0Ðé0q"Lš¤Ú"ŸˆÏ‡ò5\Í‚ÍÔÏåË‚¶mõ&OÖ}û,-¥!!YÑÑ£þþªÙð¦U+Ø¿_…!"¤,“ÆŽkªQ ìáªÑ_qçͳJNfä2¿ÛÛùûos{û/*_Ø»Wñ„¡úNQÃ¥+¦?hì᪇þOOæÀVÉÉ" ))óÌííkt¹­­’ãCHEŽ8i>PˆR`—bâèèÓ¦Ù¾} 먅Eë}ûºöïϦ:0„(!.,™†Î“Än%$IllìeOߎ…¾}u<=mß¾-¢ÓeþþÚïÞÍLNîÚ¿¿rï‹›üãÐTCÇÛhæ‘ÚÊÏÏúôiÜÿ½zõJ,¯)Û[‰lòØØw“'Û½xA=½?›6Õ^±b€··’n‡P=¢Ù5Ü:Ó,---..®,ɦ¤¤T8ÁÈÈ(55•Í&ù7{Ù«W´5kè.€\.x;`€Ûñã`nNî]ª¿·n=ãÅ‹ä!Cþü“êXÈ×°z¸W¯^ |öìÇ«þÌyóæ‘œm>LŸn~ç˜ÌôAƒâúô4kV}Ÿªˆ¹è “Iu JѰj¸^^^Û¶mûî»ïhÕ¦9ƒE‹‘uSybbÁ°aàâbyçŽಕ¼}kóǃgÏ®> „ i&€ƒ³3Õ(EÃJ¸àîî~é񴯯Ø#F(òÝ—YoΜ9äì–‘!š2EæädüçŸ —ÃÏ?ß9ztPz:ŽâB¨J"€Æöph W!66öÇLHH(P__?99ÙüÛêªDffÚÔ©Moß±XN£]d±Z?î2jÔ·Å‹æ;Õ¸ñ„¬¬wóçÛîÞMu,äkp=Ü2>|X²dIBBãóYÛ³fÍú¦lûñ#øúJììšþý7!ÃèÑÜ[·†ðx˜mª †T š;J¡&Ü¿þúËÕÕõÖ­[­Zµ*?üKOOoÉ’%ul”ÇK=Zbk »wëÈdWX¬ ëÖÁ™3zôÐÆ%ª™‡›fͨD)\•H$¾¾¾ƒ ÊËËûñÇïÝ»7hР²OçÌ™ciiYëFóóaùr¹M³sç´ÅbQß¾ãÅçX»–ÌÐj4º†Û°ö4ËÈÈèÞ½;èéé…††* …BE”Åb}øð¡v-æç'OšT ¥¥ØO,¾I“3  òCG¨aøS_ŸÈ ¦:¥h@ãp£¢¢¼½½srrš5kvæÌ™öíÛ+Ž3™ÌæÍ›¿zõjêÔ©5mN ïÚEß¶Í>/›4q káé©™R-™ ,Õ(Eƒ()Èd²åË—0 ''gôèѱ±±eÙV¡M›6L&ÓÏϯFÍ•”d/^\ÀfÓW®„¼Œ?þÖ­[:::¿þú«Ï—oÛµkgffÖ¤I“¯´%æoÙbrø°yz:Äiiµ8ž5dÈåDŽPCTÃn|<ìÛ·nAj*“ ööpû6Ôü—TJP]ÓP®k×®)ÆxÙÛÛ?xð ªÓnݺõîÝ»ê å;vä°XŠZ-Ѿýµky<ù#Ô°EÓ逸æÍêNÚ½›øÿƒ€(û‡™’BqçΧˆÜ\•^#›pe2ÙÚµkcl˜[ç¿t‰ä¿¿ÄÚZñÍ{Î`D/_NÈ夋*õ€ß¿_å‘‘ö)ŸîÞM±yó§„›ýéSssÕ„]Cš™p?|øÐ»woÐÖÖÞ¹s§¼nùQ*%à7jTúsr*8|8çãG²ƒE•ãæFOŸVyB‡Ÿò©‘!‘A¤¤ººDjjé9Né =z¨ äšÓÀnttô?þ˜žžÞ¸qãððpÅ8°Ú‘Ë?ioßnúñ£!@ ƒñ¯—פK—Œ4t'Q„ÔHõ5ÜìlxôèÓ[Pì Ñ´)””|:Þ¢ÄĨÙ"85JA.—¯[·®gÏžéééýúõ‹‹‹«u¶%8{VÞºµ¥ŸŸéÇ"kk µär'GDÐ0Û"¤d</õÍ€ªnRÒgoML*?­eËÒj–p5§‡Ëãñ&Ož|ùòeƒ¸lÙ²Ú.~˜³w¯Ðß¿ Gà^qwïqìXã¦M5sR7BêG"‘”&Úª.ŸÿÙ[z]FL¸JuïÞ½±cǾ{÷ÎÒÒ2,,ìû￯ÕåòK—èf÷î—ÉäìÞm4eÊ8勪œ¹¹9p8ÀåV™påò5T¶%šš%\Mxh¶sçN&“ žžžéé鵺6ÿüùDKKE}]ffÖ¹sÒ³gJŠ!ôuúúQTTñxXÑ¿?¡«ûÙ¯ò_åÅÇ„¡¡Ê¢®¡úÝÃÍÏÏŸ:uêÅ‹étúÚµkýýýµj¼»2ÿòe£-[Œ££x’E‹ÌÆ(5`„P5âãã‹‹µ ²’µkš Azú§ƒúú`cSICÍšÁ† `f¦¼PëˆêŒ_wOž)‰ðOÏž”äzòd‹”0Bè«Z·ht]]ªQ–ú—p‹ŠŠ&Nœ¸`Á‘Häçç÷ï¿ÿ~} ˆ‹ãvëfܧ~L °X’E‹Òÿù§Ç­[Àá(?d„êõëןŸ?nܸ{÷îU’m çÎYX˜> EE0xp̶mÝ22ÀÍŠ‘rE ``xêÂø™€1çB&E£ò--­víÚ•½íÒ¥‹\._½zu¦òK«—Ï€ ʾU*ïá&&&ž:uêÚµk,K,óùüiӦ͞=›¡ÌÚJrrò˜1c?~¬§§·ÿþ/ËR.÷õO?¹Þ¾mÈåÀ}}}«C‡lÇóP^LˆR‘˜›ÛAÏÿ¯I\D€1tj·Ð1ªµÎ;GGG€žžÞ… ¦OŸ9bĈ»wï²X,åÝ— @®­­¼[®¸¸˜Ëår¹Ü¼¼¼ ÿ[†ÏçGFFºººV‡Ëçó.\¨££³dÉ’¼¼<ÅÁ™3gÀìÙ³•7<íܹsÆÆÆàèè[ñc€ ä3™eûå^¼(“É”¢\ª„h™FŒùðÙA9AˆpOå Wd“Y³fÁår`üøñʽqh(@x{Wò‘LFœ9CŒõÙ8\[[" €8}šÈÉQn`_xóæ§§g ü,Y²DqÕg 7==ÝÍÍF£………•?nggL&³Ž»1VK,ûøø(vg3fLAAAùOåÁ oo¡¡âï÷)“ysåJÒc@jh~a›JDSGƒ”t:ýÍ›7Š#Ïž=Ó×׀݊]r•äàA€˜1£’ «\ €WbTUÈÏÏŸ={6ýkóâš5kV\\úßñ§„›••ekk þþþå•J¥ŠJ¹³³3駤¤(‰êèè8pà³Ï„BbçN‘……â/TÚ¦ qíšT*%=¤zB9±3ŸØÎ#.}±Ì´‚@N8¥©Dög© —Ë9ΨQ£Ê --­Û·o+é¾—úö%{x(©}exòäI‡ª—¤ÑhÿüóOÙÉ¥ W$yxx€»»û—¿ªßºu+(((##ƒÜ@###5jööö˯H+‘<Ÿ?ÿÃÿ—vOãpþš3GXRBîÝ…vç¶©„m*1#»òž‰ÛT¢kí¶ï@d8pàÓ/ö*_¸p!XXX(i¦ïŸ=zÔloó¯ …k×®Õ©lS®iÓ¦•?³4ánÞ¼Yññ… T_ù2 AƒrssÇå‰xÏÂÞ^‘js5"Μ!°V«Y>J ç´¯$Ü{%„m*чäñ¨þý÷ß/J$ņ]ºtùê’&u±i@¬XA~ËÊÄãñæÏŸÿå˜KKK.—[þL ‚Ëå*XÙÛÛ+£J[AFFF=@[[{çÎ¥w”JSRôô©Vhk{uúô’b,ài Å¹¥Ù¶š„›%%lS ç4¢¤Ü™RâT¡jbDUÊÍ͵··‡ÿ?O#Ùš5±nù-+‡D"Ù¹s§‰‰ :88”O¸Î‚ Ž9¢øX)ƒŸ‹ŠŠ233€Æ—þ•Ës÷í#\\J ZZ’#G±XÙ‘ Kë¹DÿÌOÙ¶ÂWæçõùÙ„m*±*É AD‹r?Ë¿ˆ*±±±zzzpøðar[Žpu%Mn³JrçÎ6mÚ(’§··wzzzù5c‡ öå%@ÄðáÃgœ>}ZyÁI¥R???E¡ÿþ999„\. O60(}Îhmýð§Ÿ ÿ? i˜sEDÏ ¢ÓûÏ’¬sÑ3£ô+çó„Ë—þyD—tÂå1$“8T@àSõqâÄ ÐÕÕ}ðà‰ÍþÕ²%ðxâDÛT†wïÞ=Z‘Í\]]oݺ¥8>}útE.åp8YYY_^A”Í‰Ž‰‰QR|YYYŠÒƒÁ ”Ëåo‚‚DíÚ)Rí:ý…!)éîH}\-þ,áVUR@êO1<¿I“&ÙÙä}gÏ&ˆÒ$›H$Z»v­b„œ‘‘ÑÎ;Åå~_ºt©"—9r¤Ò˵ ;;[q’™rv¾sçθqã222¬¬¬ÂÂÂzÊd™N©©––ü9stgÌp±²RÆ­BJüêÕ«;wîŒ;öï¿ÿþêfW5¢Þk)\½zÕ××÷íÛ·4ÍÛÛ{Ë–-VŸ'.‡Ý»wŸ:ujåM¡~ ÷ï߯4+ ‚ºý4Édk×®U|'úôéópëÖLE¯–G£Ýè×(ªb&ÒPØÃÕ$YYY7†r3©¾ÑÍÆ €§K—’Ò‰RRRʶwss+?´¶¼ƒêêêÆÇÇWÕÊx¯t9÷3gÎÌ™3§? òòò† —ËΘqE,î°t©Ur²ÜÈu³³{EE>®û„¾‰”€‰aIÕq4H–––çÎÓÑÑ :}úô·7ÈJ€®§÷Õ3UF(®[·ÎÅÅ%""ÂÔÔôÀ?î^Å´¦¦¦U­Ü @ÄÙ³g¯íììÊϬ•Éd7nìÝ»wqí‡gEGG+v/ïmbòˆÍVôjK˜Ì(œÿOD é=ÜÈbÂ6•ðÇG­ÔÙ½{7èëë?þü[Û2„ ÔfˆˆÅ"t:ÝÇǧlÆ@URSSÅÕŽ°*ø0ùÿ›#´hÑb÷îÝááá6lprršp¥”¢déèèÈãñ¾©¡~ýâêU’⪻¤¤¤²BçÎ?› û J®\.?v옧§§‘‘‘®®®££ã¤I“îÞ½[Ûæ¸\îСC[œr]Ý;f~1G5L¤'Üe¹ÄÐJ†ß •*))Q¬'Я_¿oYðä‘p艱ÕVaa¡bž®™™Yhh(‰ ’¹MzLLŒµµu€€M$'“x Tß‘žp§~$.â“W5––¦æ´víÚ:7§§G$Ÿ:E^\µjcc ÃÇǧÂÄÜoGÚ;‘‘‘Æ “J¥W_:çÚ^W*623µd›ÐÁ˜&t0a€ Lè`L/}¡¯^ÛM õUÍ.;Ú4¤Ä±QMÙÚÚ†‡‡{yy­_¿ÞÍÍmĈuh¤MË–ðä‰}Ë–¤‡÷U/_¾ôññ¹yó&tíÚuÏž=å·½ i 777W*•@†CóbK›Ò£‚ê.& Œé•}1*1c¨Ùv@HU¢°Š A¦¥û>ÌÍŹЅ µ(eì8ª‹Þ½{oܸqùòåS¦Lqvv®t7¯ b.ŸÏ_½zõ¾}û$‰……ů¿þêíí­˜EF:ÒnLLŒâÅ›¡]Ll›Žœ2màãµMÍòeP ‡|9äËK_(^È@@€ˆ€ld˾޾A¹®±1ØŒÏÞšü?/›0€…û¯¨± ßñ•óq—úeÙ²e±±±gΜ1bÄýû÷ŒŒjuyê›7Mrø|Õü%âäÉ“+V¬ÈÌÌÔÒÒòññ P¬D£$¤%\sss˜>}:ŸÏ?þü¡e Ž,_4pà@__ß }úTu•(Í¿Ÿ}É*9˜-ƒ"9dÔ,˜šwœÍSR*£ÏOI©v;È4),Î…Nº0¼Üpíãæ !0áª)väÈ‘W¯^½xñbÊ”)üñG­ºŠ:ÚJ ð“gϞ͟?ÿßÿ€ï¾û.88¸l%å!-ávvv«W¯NJJÚ½{÷áÇ#"""""Ú·oïëë;~üø/'ÿéÒ@—5Ûš²@e_OÍ\Y-:Î¥i÷«©Ù”¡–{Ê×7nLЧC±¼ôm²6ñ ? òå KÏÏ7áÞ–¦~v˜mÕšÁùóç;uêtáÂ…   ²åj¢±©)ää˜XX(/<ÈËË[¹råÑ£G¥Ri“&MBBB† ¢Ô;–¡)å·[½zõÆ7lØàïï¯8RPPpüøñ­[·fdd@Ó¦MgÍšõóÏ?³ÙlRîXštœ³eðQ¢ÚüékÒq¶`€˜˜ªvªVr+9>ʶ™~z[B@Û÷ %à™-èãßg}¡X«022²ÿþ5½ÌØø|ÈÏcceD%—˃ƒƒ7lØ——§££³bÅŠ¥K—ê«p¾+i ×ßßÓ¦M7n\µjUùãb±ø÷ß zþü9N:uÑ¢EŠ))WóšFž jÖc¨MM£”¸õ¼ºúO‡ùðT|9ÑÁQºê†`Uîïâ¹gD[S(úëÖ­ àp8=R¬Y^=‚ Ät:€hJ˜Ý{ÿþýyóæ=zôú÷ï¿{÷n'''ÒïR=ÒîªU«~ùå—M›6­\¹²Òþûï¿-[¶\¹r… :>pàÀ•+W*6R«/ªÊΊÎrÙ‘|9ˆÉè8[h}Vë`7°'E÷…0æ#8iõÆT‡‚êD.—6,""¢mÛ¶ÑÑÑ_ÝQ\"k1™4Éàk[áÖJNNÎâÅ‹O:%—Ëíì삃ƒUVC¨@ueIOOOOOÏ·o߆„„:tHQÞuww÷ññ™0a—Û©¡šWœkÞqέMŹA¢³ÓÈ‚Ýÿÿ¤É’Á­¯Šg*è[Ñéô°°°Î;ÇÅÅÍœ9óäɓ՟¯]úÚ$f[™L¶gÏž€€Çd2—/_¾lÙ²¯¦~å!­‡»råÊÍ›7ÿòË/+V¬øêÉÙÙÙ{÷î ÉÍÍŸ3f¨²˜¢>*dçl|”V’šyr|CÇÙ‚æŒJR3‡ÚêÚqþ)þ€·!¬aƒ ® ª6q>å_¤þâãã;wîÌçóCBB¾²î`a!’rëèèèùóç?yò¸k×.ÅJ4"-á®X±"00póæÍË—/¯á%"‘èôéÓ[¶lyõêM™2eÉ’%ŠeÆÐ—jÞqΑAÍ¿¯j;Š®P¿æÃõ(”ƒƒ Õ‡©F ±ä]ß]¸paäÈ‘ZZZ7nÜøî»ïª:-çõk³V­xt:[VóÇ%•ûøñãÒ¥Kûí7‚ ìííwíÚEU ¡ÒîòåË·lÙèççW« ‚¸qãÆ®]»å]aÆ-Y²¤S§N¤Ö` ‰ŠÅåÊGÑÉAZûŽsi¹šQttÐÂ~(ú¿eË–mݺÕÒÒòÑ£GÖÖ•?Í|ø°q§N iµÃ³«%‹wìØ±yóæ‚‚]]]??????=µY`—ú¡¥4­OŸ>}úô‰‹‹Û·o߉'Ξ={öìÙnݺùùù |KrlÛ¶íöïß=tèPGGÇyóæýôÓOÖ¹5ž2ÖjúIÍk8ý¤žR<@ëСCLLÌâÅ‹ƒƒƒ+9éRx÷îÝܹs#""ÀÙÙ988¸wïÞß±rVRPüÊð믿ÖjbIUŠŠŠÂÂÂvìØfffÓ¦MóññQl „ê…ê³sY¹ƒ¬QtŠì\Vëhh£èê…¸¸¸nݺ ‚#GŽL›6­Â§oÏœq;ö­žž“àk«^•#‰6oÞ¼uëV@`hh¸aÆ9sæhkk“8iÔ¨‡[žÁÏ?ÿzôH±f¹B«fÍÀ¥}ûš´“’’âã㣨!¸ºº÷ìÙS9!“©~ÄÚ·oâĉõë×ïß¿ÿàÁƒŠò®››Ûܹs'M𤫫ûõ&¦PFÇ9G9g\‹¤DÅñ*;vìxþüù¿ÿþ;nܸ¨¨¨O“žjVà …¿þúkII‰‘‘ÑúõëÕ¹†Pi5ÜÅ‹oß¾}Û¶m‹-"¥Áª=ztÇŽiii`aa1kÖ¬ùó盚š~õZ„ªR–?¥#o]Åt iÝÙ"x)†%&`P®TðñãGww÷ŒŒ ??¿ÀÀ@ÅÁØõëÛ¯]ûÀ̬Svv•­=»|ùòääd6qâÄ-[¶XYY)û@"Òî¢E‹vìØ±}ûö… ’Ò`õärù•+W6oÞ¬XøœÉdŽ3fÅŠuYd¡Ú¨Õ"Î5WóŽs k/j¢˜€Îé`H‡Ul\n¨Ñ½{nƒÐÌIDAT÷zöì©XÜj̘1ðhÅŠ1VV™™_¶óúõëùóç߸qÜÜÜ‚ƒƒ»wﮪ?iÔº†[²òîãÇwíÚvòäÉS§NõêÕËÇÇGMf• T󚆈ø´Å ‰£è ^-â¬OƒÑúp´ææÀ)]XÏæÚ]ºtÙ±cÇœ9s¦OŸîâââââÒ¡ukðø¢[XXèïï¯ØÇÔÔô—_~™6mÚ—‹k× õ5á–qww?qâĺuëvíÚuäÈ‘ëׯ_¿~½]»v ,7n\}©ì Ĥ•®\_í8—Õ:Dÿ?³†1TßqVÔ:LèJ\ÄÙÛŽpW^Y0ÕƒfÏžýøñã#GŽ >üáÇƕÕpOœ8±råÊŒŒ :îãã³fÍšz]<$­¤°`Á‚]»víܹÓ××—”ë€Ïç;vlÛ¶mïß¿KKË™3gúøøp8ªBBˆtõqçñ!Z@ ̰‚ ÃõA$vïÞýáÇC† YÁf{œ8qËÉéû7oàÅ‹óçÏ¿}û6tîÜyÏž=†‘‘Â××÷ĉaaa ½ñ/ÕûnyFFF¾¾¾³gϾtéRPPЃ¶mÛ6~üøE‹µhÑâ«-rÙîÚ¥/¾Üu[R¨ivf˜0À˜Ft`Ò>ÛÑŠðB £>ÀDÃ&GÏþ1¼O¯„/ÀÂÖ¶eË–YYY ÃÇÇgݺuÊÛ”ëôéÓ@£Ñ»©€&Ü2Š%σƒƒËv´T,y^鎖Àb±²²²ÆŒsëÖ-fæt#Ti˜2À´Æ•‚òçÒÎre5 žòdWY^Vä^@h!D4ûnâ™HíÑ@&»™еk×={ö´k׎¬?`¥ G5ÙˆIæÍ›ÁÁÁd5H®ìììÀÀÀ²¥ìííy<^…ÓÅ_˜2e %q"¤IÄr"[J$ˆ‰|Â6µò/»TbÂ"¢HÎ22ƒ±gÏ©Tª‚ðŒ <<\÷R ­,B¨_·<333??¿”””ÐÐPWW×”””åË—ÛÙÙùúú¾{÷®ì4ƒÒÍ[Ž?^6!T7Ú40c@c-8YTɧ¦ X` ÷mà7 ¤Oëû}O022š9s¦ öÜ*)))((°°°9r¤²ïU¦¡$\I“&=þüÎ;ƒ.,,ܽ{·ƒƒÃ!CîÝ»åô÷÷¿víuÁ"¤!ó!óó%Å[jÃ/øÏš|ª/ÿñÇ­Zµâñx‡RAT?~€Y³f©rðhÃJ¸e<==/_¾÷óÏ?kkkGDDxxxxzz^ºt©ìo_&“9òåË—Ô†ŠP½–!…½¥¯µh0˜§- ª1L0ÖçÙ‚Á`À† µY¡±nrrrtttfÏž­ì•×@®‚››Ûâãã.\hdd=f̹üÓ€òÂÂÂÑ£Góù| ƒD¨^ÛăÌàk w­!Ä ºT½ØÔÈ‘#;uꔕ•µwïÞ:ß1111 ÀÓÓ³_¿~={ölß¾ýž={d_ì“–““3nÜ8 ‹:ߨ.È*Ïš5 öíÛGVƒ*& CCC+ýÛŸ¿páB%K–äåå)Μ9fÏž]ÛÖ”¡A÷p+øçŸe """V­Z¥úxªïZ3áw ̪ÅZh^^^={öÌËËÛ¾}{­î•‘‘áéé¹sçÎãÇoݺµl~éÕ«WàèÑ£I³j¿&\€>ôêÕëèÑ£U°eË–ððpU†„ЯS>ذalÛ¶-»êu+øðáC×®]Ÿ={¶jÕªqãÆ•—ÉdŠ^”ƒƒƒ:d'L¸Û±cÇ»wïVsAÓ§Oôè‘Ê¢B¨Áòôôôòò*** ªÉùb±xĈïÞ½swwW»ï¨ãÔÞ¢"ؼD"(,àñ A*…’ A"¢" ÈÏ==Ø·†­Ëär¹½½ýãÇõôôÊë·ÇÈuá̙ǎ—Àر0e ôì MšPRww÷‘#Gž;wî—_~©~ÄÇSÌQ²··WÙ’u¦Ž ×À á—_¾~¦­-œ?îîu¼No_³ëU΃±c!4´4Û@a!°Ù £CiXHù6mÚtñâÅÇ/^¼¸Y³fUváÂ…‚‚èß¿¿ú—4Õ´†ëç#F|åœ^½àÑ£ºg[DºÃ‡FûÊ‹ææàì #GÂÆðêUu &%Á”)н;Lœøéà•+‘*=‰TÏÉÉi„ ‰dýúõÕœ¦Ø¸¾ÿþ{•ÄõMÔ4áÒhpü8¸¸TyÂâÅå¶XFÔëÛ‚ƒaΜJ¾qÆÆ`l FF CNÄÇÃùó°z5¸¸ÀwßÁ“'•7¸f Ÿ¤Ñ¾º¯+Ò:::§NzUõOæ„„Å [[[UÅUwä¯éKCC¸pLL*g2¡gO˜:êçžFšÌÎæÍƒ˜5«âG>@~>€D))°u+èë—~ôßàá‘‘/àÂÐÒ‚Þ½•9ROvvv3fÌÉdkÖ¬©êœ²¡cfõ¡ÿ¥¦=\…æÍá·ß ÂSG¸}îÜxÿä5ÛÙ ©  š6…%Kà÷ß?‰`âDÈÍýìÌׯ¡¤llàÿ+¸¡†ÈßߟÅb?þÁƒ•ž «[:S8//¯ÒJJJ”\í©u€Aƒ@±JbYÃàï“&A@¿~Т$&’{O¤ ƒƒ“Ó§·<?þÙ ÅÅð©#Œ&++«¹sç±víÚJOhݺµâE¥ùÌ™3sæÌQb|µ¤î –,áálV6‹R)4m "Ì›qq¤ß)Q…žÿüóÙ[Åsé´4(ßAIO‡ƒ•R'~~~FFFW¯^Ul(YÁ”)S/‚‚‚ʯ3%—Ë7mÚtðàÁ•„Y#ê[Ã-C£Á©SP6|K(,}ac¯^Á?ÿ€–œ?!!0y2€@Ê_Ú ‘ ÂVUYYŸ½µ¶†aà¨/‘är¸t üýqÊCƒcjjºhÑ"ð÷÷ÿòÓQ£FMž<ÒÒÒ:uêüûï¿oܸÑÙÙ9!!!""¢ü"×”«=\ÐÓƒððÒhe h4P<™ìÒüü`ùr€#G qcØ·O 2I?_”úË5þCCaî\¸r,, KHN†#G@OOe"u±xñbssóèèhÅZb;vìØ±cžžžYYYË–-[½úíÝ{XUUúð/ü‰ €·@ДCMÈ.hc¥xA¥§ȸhˆ cÈeŒ†QpÐ&cPÇJ$$gz*oSŽVŒ†ŽJÉ%0(AÔ€#w<|ìý œ/p<û@ëóðÇ>Ë}öyA}÷bíµÞWRR’žžžžžÞ9Âk qáC·~{ö`Þ<´¶vó§ööèÜçôiÔ×cäHxóMܸà`1Ìi•f;VûKKlÛ†mÛô`¨ ´víÚµkׯÄÄx{{k­ß522 ì[0d}£‡+‘ ÝÚÃíVFòóáão¾‰˜”•À_Üù½‚Þh4øê«.-O?­P(B_°råÊQ£Fdff*KÏõ¥„ `íZøúÞù4gg¨T ±mÂÂàêŠúzxyaÔ(ˆÝ Dj*ª«o¾2þþÊE#îîxÿ}(+C[›’ö3ÍÍ ÑѧžêÒž­ƒ‹··ÃË AA:¸” ¥¢¯¼‚ðp˜9Sþ€§'–/‡……¾ã166–:¹‰‰‰zØJ]çúÞ®n=þ8Þz '€«+œœ0{6Ì›kkœ? JFØŸaçÎ.µ¾.\À«¯öö²ÙÙøì3±X—ÊÊä•Ö RS‘šŠÆF¸»ãÒ%ܶV¢>,\¸ÐÕÕµªªj[œ0ø íávë@AFŒ€ZÁƒ¡Ra´µaôh<õ”X½¦& .®KËŽ8t¨W×,, z¸:på H45ÁÉ !!¨¬„½=RRpæŒ|?3E[ÒÆeIIIµÒ~0}‡H¸Ý°°ÀÉ“(/‡J…ÂB47£¶ff¨®†­-BC•ޝ‹Š‚³s—–à`íE÷¤²S§ŠRô½[[äæÂÌ  ”—®\)ÿ h8¼½½===kkk“““•ŽåÞˆ„û?IU{ 55¶H?zUUrÑœ3gàá!÷„‰ víê2Û¤¦¦W_ª«åAFá^eeaæL|ø!  •JF{çìÚ{{e£»i+õ-[¶ÜýVê†@$Ü;³°{dþþ((ǰ>ù'NàÛo 3óçãÀ%ƒì[ž|¿û]—–Çqû¢NUUˆŒDXbcáå%?Û”<ðüüîKœýÒÅ‹HH€8v ÒÒ­˜TW#$DÙèîÖôéÓgÏžÝÐаyóf¥c¹Ô‘E‹Ø»w¯®.hà®]cv6 H28˜7o&É”úùñøqe£SØÖ­º|57kŸÓÔÄq㺜3p »¿`f&mlxäˆüò…hlÌŠŠûø-ô3mmüüsþã$¹oº¹‘ä?ð½÷x劲ÑõP~~¾±±±©©iee¥Ò±Ü-ÑÃí¡¡C1w.¤ÚÇë×#-MÞõ23,o^__Q¥·{jW¶mn†¿7³ñöîÅâÅxã ±qï=+.ÆÇ@i)fÌÀÊ•è耗 vv ÄðáʆÙCÎÎ΋-jiiILLT:–»¦«Ìíëë 33SWì£JK¹c‡Üepp À3gHrñbΛDz2’lmU2Âûçúu¾û.W­â¤IÚ=ܹsË÷ß×~KHˆö™..ŒŒdV–|Bi)ÍÍéáÑå]liÑÇwÔÕÕ1;›$ëëibB•Šõõ$éáÁ˜64(Ž©T*“ÒÒR¥c¹+:K¸ ,°oß>]]°¸p»vñÆ ¶¶ÒÌŒFF¼z•$ÇŽå„ ¼t‰$ËË©Ñ(¦Îœ;§=þ¥¥¶–#GvsÚ¸qò ¿ý-›ùWèVk+srädjgG€ß|C’ ð7¿éçc/AAA”䮈„«'••”~6W®ÐÔ”––ÔhØÜÌheÅæfvtð£ØGîÓzÒØÈ©Rñúu¥C1<—/óàAù¶ýôÓxø0IrÆ ææ*þ\¼xqÀ€ÆÆÆyyyJÇrgb WOF‚0|8êê“ccTVbôhŒ SS”—ã…ðë_@}=~ÿ{1íAlÜ«­¢ééøúkˆŒ„\iÚ48;ËÓfß{'NÀÅEÉ8õi̘1Ë–-ëèèVC8‘p0`yÆGI‰\‡»© 3gÂÃΞşþ„„(*‚§§¼ŸEkë/«ž¯Ø¸@~>ââä™[©© Âßÿ˜6MÞwjãFäçcî\%ãTкuëÌÌÌöíÛ÷•VM{Ã#®ò¤§í“'ã_ÿ’ÿ/ƒ ä‘_}…ãÇåNͧŸÂÒR.Ô]QìlTT(µ>ü7þç?˜?ññpö,ðÑGðì³ðóƒ«+#'/¾¨X¨†ÃÆÆfÕªU^ýu¥c¹]Møøø8pà€®.(H®^å¡C††²¥… ³²øòËljR:,ikãÿË£GIò‹/øàƒôñ!É£G ÐÝ$‹‹¹z5÷ïW2NÃW[[;dÈÇŽS:–Û ·ime]IîßO__fddL ÆÇ“db"ÆÅ‘ä¿ÿÍ7Þ`~¾ráöZ]ÃÂøÐC´´¤‹ ·láJÇÔSÒ}âòe®_Ï×_'ÉÜ\œ<™$‹‹ ÐÞž$ÕjîÚÅs甋µZ¿~=€iÓ¦)Èíô0áHK¬n1gμµ±¥¥¥¢ÏI1 %%ܳGN¬¯½FssîÜI’¡¡˜œL’‘‘9’»w“ä±cÌÈàÅ‹ÊEü ÐÜÌÌLù/âÒ%F;;’¬®&@++’llä£rÉ’ÔhX\܇o'Š»~ýúƒ>øó,dPz8†ûé§ŸzzzžŒÝ» ½Ï<ƒ @‚ÄâÅX±7nÀÚ ¸v ÍͰ¶FRvî„F33äåÉï56Æøñ=ÜAJ0hРèèh±±±»qKÏòtCCÃðáÃx{{çää|þùç>|¸±±ñ­·Þ²µµ°Fn @{;¿ûNÞݾ‹óë¯IrÖ,üç?Irölò:¥… ©RQ"Ú¼™<{–$srxâkk•ù.ô¯¦†rÇóí·'/r›2…²±‘$ÍÍ ÈC=C‡`UI.Y¨(yqUUÿYáb°š››G àÃ?T:–îõ| wãÆY{Ö¬Y®®®–.]jmm-5š››WWWë0Vá~Ðhxé’œDÒÒÎòr’œ9“srHrútÍŠ 12 ˜·ß~ÀÃ?ÜÞÞ®t,ÝèyÂU«ÕÆ »Mß922R‡ ú×Ò"'Ž/¿äîݼv$ÃÃ9}:KJHrÊrOù‰'ðôi’tq! /vš:•€<ËbêT,ŸÀ'žW ÆÄÐÏß}G’))ŒŽ¦Tþé/at´œìn=NKcR’œà¶lat4¥;{|<_yE>'<œ^^òªÖY³ø«_É×wt$ Ç?~üͤ)µK7 ©„ôœbÆ Nš$Ÿ“œÌ„^¾L’%%rv J[[›ƒƒ€´´4¥céF¯f)$HSó»cnn~Yú‡)ôkõõrR>r„;wÊC qq|é%9iúùÑÁÅÅ$9q"ž?O’NN7“š³³ö±ôðî¥U>ª},Ý {¬Ë±J%ÐÃCN¦))LH‡rsyîœaõÊ…»·gÏcÆŒi1¼GF${<þ«V«íííúé§ŸÿQTTÔ¦M›z|e¡¿ª¯ÇàÁ06Fa!ZZðÈ#05Å'Ÿ@­†·7,,šŠk×°t)† CZ®\Ap0FŒèrœœŒêj¬^ [[¤§ãòeÂÚ™™¸z bøp=Šöv¸»ÃÒ?þˆÖVØÙuÙ¿Rè¯:::üñüüü””iA„áèU””«ÕhaaQ^^>tèÐÞ\Y¡g²²²|}}mllJKKÍ imxo—ö®ZµjĈZ«W¯ÙV¥,X°ÀÍÍ­ººzëÖ­JÇÒEo®¹¹yDDÄ­-VVV¯¾új//+‚ÐÒ³M›6ÔVê:(^f%Õ,„††ÞúRAÿž}öYOOϺºº-[¶(ËM½Õ$&&¾öÚk† R^^niiÙûk ‚ ôFnn®›››¹¹yiiiçú€Næÿô¾°O7åä$»bÅ ‘mA0S§N3gNCCÃÏgL:tèÔ©SúI7 ×ÊÊ*<<ÜÂÂbÍš5:¹  BïmÜ¸ÑØØxÇŽ•••ÕÕÕÁÁÁíííúGgÈ#""Ö­['&'‚`8œœœüüüZZZn]¥µbÅŠšššÒ–Dú¥›1\AÃTRR2iÒ$’………ŽŽŽï¼óÎòåË9rä¹çžÓs0:ëá ‚  ñãÇ/Y²D£Ñlذ!//oõêÕR»"C ¢‡+B?WQQ!Õspp(..–333}}}õ‰JÏŸ'‚p_eeehjjjmm V«Ç÷Í7ßtf[ŠŒáŠ„+B¿âèèhgg¦V«osZßž¥ ‚` òòòÜÝÝosŽ"=\‘pAè‡ìíísrr’““xànO=\A122 ÿòË/¥= :·¸•ˆ® ‚޹¸¸œ={ö¥—^Òš‘%® ‚î <8##ãÝwß533ël Wá~Y¶lÙ™3g¦L™"½c¸‚ ÷ÑĉO:add$j)‚ èÃÁƒ+++CCCõü¹"á ‚ è‰RAГÿÁm¶W`nÇIEND®B`‚opengv/doc/addons/images/point_cloud.pdf0000664016516101651610000002721413344612246017311 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝœ¹²e»REýúŠmcl–zé °yÏ$°ŠŒ*0ø}昩՜&°ÊºqãÆ©Ì­^Ùgjý×ëx§×ÁûïÏß?þñoãõÿóÃØ×ÿÇÒG}Ïþ*MŽõú}crz·Z^¥×ñžë•W}·!0Õw/'øóGi3½K¿~o©¬»û ï è°1s¾Q_ç5µ÷á c†V½„»Å^â9§Müüñï?ò|—Ú_ÿ»·ú·ú«nõ?üý¯¼µ4z{§ôš³½{MÚÚ…iù]F{¥Qæ;Õ×Ìí].øÐó‚þH}¤wOw‹^µ¶zpÂ{zf¥ù^î#¬ÚÞs¬kŽV½Š»E¬òáÓ> Ñ¿îÞþÚ7ÇîòLå½Ä)SäZa¹#¦Éù•Ç0ÄP¹ hå=Êÿü‘G>ÞõÑ¢¯ònwïŒáÕþDÌñ ¸»/ñ™¾&Ø0ÌÇÏ×âv÷OË‘ùÛÒ_òžÌZsïµ^Ðò(Öš£¼§ýÝEýû›ß§–’æ<Þy¼FÒµÉÏY`’‘’†É´R—‚Ë»Nº¯°Æ?†{¬ö.š@Â{¬÷L5M𝴴’ÞwæÜu¬wËÂÌwÿ%68§aq¯`ËhL1 ŽànÑ¥a’YšøriOu¾úêæ}zHuta¤zª88-]ÑÜtvcÜ0Ò£[:œ…°´(ïÔ^m ±8=æÒ¹µYßZMLÑÙXYC$N®u  ÊÆQZãÕt«]K¡G—8ɯ¦ÝIâc5Ä|5I™r0e]﬊ȤX-ý¤Cm²YÆbYsjúS3#¤,-|Á>ÜæUœ-暨VàÙ¸ñ•ß·¬ƒH)n|÷˜žU¢É€uÍpŠU¦s`´±r@õ†fwÿr¸}~ÀšARB¨aËE·“¢¦qÍ5,­ßD!«³‡:ˆ¢’f Pj³U ³âJëg‡¡“=tYm)BhHtïú„ó{å|õh¯Ú‹Û_¿~˜pu³µiûGybj·xfˆÂ´…o0^¢|mç9r`ºHi”³S… uR«>1b…Ô¢“¹}ÁÞjTfO Áê- £AÊ´ñ>».C¿ˆý9™2Ãæ)bÿ^P£qÛ%O3;=´B‰µ¢žCO”TD¶Åç´Hž%»ÇBÁ”¢E$ý׈+‹¤Øq¨×{” VNçH:ó†K¡ ÕÙ”%ê}‰bÉ)÷Ðu-|¸rÁ‹ËÊÚ k9Á²¼wŒNy/xÀ‚Y#[ÇJ8[;©ÙšÑãý¥+ËL!Û(RÒi ªVåxûv„0z%ÐQÚBA&°œïB†«·h£¯ä ´1ºÈò€kRÕ#æÚÞðÏ8÷”-Æ8aÏaÛB=XJÞ4ÜÙ³ÆýKÄåäU9ܰo»HW»\Eˆ_ç7'.•hJ[,ì+ Õ׊uæ|Á> ôãÝ‚³‘u›0ج˜¨¶+Ä{!&uþm]Òa_–ôœ´ÂëóuÚ…:tòZf•µ¥ÊÙH"^•b=ôua– >bD)¶o0w/±\¿¾=%ë%w*\\×.sj0:VmŒEGÐÊÑ)üqMôï?jÒ¹Èh‰›ð~ÿ¨G²Ë|b~]ÝtJ¥#Þ׺I„üª‡¦Ð1Î ízHâI%JY7,ïŸê 1ª-ºé"ë¡á1=äÕ –µ/Áv`Du÷Ÿà¡ë d‚'Äž`TöpÀè•Ø &·ýæ©aÆç˜´h6 ³dañFðåÆû:Æãçʼny>Á6qÓ sPÍ“¦î6§íꉵ7Ù"HæA€’nÃ?%[&-V.­+ÁhC$ÌuL@Ì<”i¡S(ÖñX_‚³M¡2nÊ[¶¬ÄM›Í–‡ŒÆlÞXvM’NÕ"X´ØÝ?Èÿ0w%ü4v‹Dej%u“žL5sŸ‡ø@„…Ä›µX)¯C¦[\Àdb<É~“ZBÈ›ë)„H%F k"­8% §ó닸B„ýË F´÷¯¯ãõoÎ $r²ì0€ñ¤¤0¾¥`¤Š@”·¯#±ö€1hÆ(¸p',‘&ï…©¸Å6¿ò6ðkñî1Ò9È¿k9±ŽdçG£©òHÓ7 ¹âñZã4rz¬ˆ€:˜¿ïõ“¾Éub¼Þ$ «‡S1¦­(s]˜w½v ‚'¦Ù>&Ʉ־Ã\½´6×c䃓6w¯dl`D­˜ä‘gw(â‰Ñ̵12¢GØ9|UË&¯FÕº9s΢zšÆàŞϞuàr`]õmÍ,„”s„[SW4@þãňX³È¨ØÞ(ÍÖEïzpŒÄù€æ¸Ä,æ£ã_·˜/Û¡«N4lw¨\GÛñÙ ŽR&OƧ ”µlÕœ[È`l#j“1G›¶ÞKqè}é9®§IéáiaÀNF@-âËÃA&6µþ*’b\íãŠÅq˜Ýdpa.R)2ÛÇrÊÕàI–¿¾*í,Í8ÃZLº'FgSš‰Êqk¨4rYH(Àñ¶¸ÂV‹^’èfyƒ¿pm:ò5g$=YL¡Cã2꣯ð#x'Ê‘¼õ‘d¼oÖS{q”·à„gnø„Þ;ݘçÞ±'6Dç# \B³f‘/7ÖµÌMæAlDw*ùÞ`±õä›kXëöC¬£M?‘áË6µ °-X+—ú‹Ó–ò… wDÏÇŸÙHr¹®§n}}¾Àf$“@—Á'þ~`J ñU:Zù;Dôùõe”¦ËÓ¢ãÂ@õ1Ê8z|½PµˆYAŒi—ÌцSt!¿ªŒ¢‚Õ/óò»ˆtÇ$•Ì4Ä€S¸X0xÁ/–ñeç †ŠÃ`€< žàùÜѽô`É6ãýpDò§­@7߈†žºzϵ{ïáuùp_ó뇂ÇÉÚrô^yÓß ¡½µ† Þ^×ΛHh<ΦaµpWãôˆêÛÁ]%`„ØyþÞa£Ù-°Ç×c„ÄrOQ'¾!õâç"ëŒï] k˽ÍFääqº8Dó}F«ù—ë—®2õûoø¼… ³¯éaßâ5ÇuÍ×*6!œ‹<éäÜÆƒŒöF/BÛqÑaœÔƒP÷Q^¤¼ú"õÌà#4H^aŸ8à°ò…!ªAø}…$Ê3⧦’—ˆÉŠ„èq^R“Ø§ì… ‹C\×ÒÏKµ•ñc×—°Yý’Ciˆ&ìà~FêXW –lžæ†‰ß"Ìêu©NPIoGFú–ÅWwÃÒeJ9(óÑB”.,× ‚Ã6ÄñŽ×"ŠÂ~íuÃh£Ê„ëSè¢M˜š*Ûž: ŸÂÚÊÅÁš2¬z±·Î ʱÍ5âJ³Áñ¯ëZ`v̾™ëgkÏ娩CAé´æ"èÆ¨aFe˦²“Î.9²uçŽCË¡ÀóŠ Mu“Ï2“ÝbzÊk(¶ý’—D$ºÚö+Ÿ!ÏÄ1¶ G\µS#`"”å '&ïeÿ{óm.çO2 jÙAË,Ú ÎžÌK› ŽÒ×{©„Uhè„«-/zœbÒîÑlƒm)¸8‰ÑÅ-b Éé«Y÷8|øÖÂxHGð0tfnÄÁLÍrN†À 1¡ãêa7¤ˆ@‹ÚÂRpÒ·Ž4{HN;Æm¸œAîÍk˜ÉšòÛ£)ÓYF%=^’œf/ Ž÷¦{vOÒ]]±iJ×Q—Ô]žÑB)–_(c95Ü þdîþØP¤Ï?m!9ß‚ãÌä-Œ(gâ´ðŸiULˆ)Žþú¦_‚Ahè5báh$Ö­]6È­.Œ:¢‹«9¦VHÖåæ•Ëæ-Opç˜n¥£35JÚMûÚ¯@—ÎûÆÿáOÄÊgƒ é׈L¦#ã•siH ßÌ‘\D¶Y“1†×$äºÊ þü1¹KÚb OkW÷Ž ~þ¸1bíè GÃ5Æ5Ź„³ÅµÄ=§M`ÿ?Û'ýE·Í}ÿ…·v•Îf \¯á¼ìû÷†î’=#¸ã,ªfºÓ:NçÊd¼aϱF‹ÿY¨êTIq’n$†\Ž$§ÈæÉÈv㯷A‡Â3Bž¶xÏäü=ú#Sd‰i(=”‰€´zÁ”#ùàX!2'âHU‡SŸ´':LI)‘kWPíS Ùü€I»Ã‰À74 [*˜Ð‡“] ª4j bI5,.òê+ÑÂgAcU–(J ¨uG$]´å`[i›è8çK&œªœÊ"Iý0‚n¤ÇM¬pš.{qÓ!›â:Îy8 wÂ>Ø«8[Ÿ`ŽB÷fp^Sç˜@SfìÌæîô•Áàõa³{6!–ÆL1Ü[tgÀøGMǺbú×aŒíTÃP U@sŒµMÍN:;` 59øew ÎÒÒ2©”û£È«ŸXBrŒ*@&Lù À¾Z SÑ8ú¦Ul¼Úma>1ÍašæoW,™œŸãž×v޳SéÚù² CÎÙSë˜Êü„xðó¯  ,LÎzdsø‰©”eÛÝ:2—œqÆÔ.˜øI(¿v9 n´ôÑãÚñ qKÅ)ÈpMaÀ¹Âk¦ùV*›“£wØ©‰)‡]jmm‡]²Ã_›'WÑíÇaBMh2Uº´|Áž)èp½i7y[Ì7ß™Ék _W½]‰ÇåÏv Xc8=S¸Š6zsüÉ…ä}…ä傽¯ÎrîÓv“Ø<…°$xOQÃXŽã‡Ä©ïðõìë"Ý=_Ÿ/tW½ÎàÔiƒ˜Ñ¦3F5"vŠ?V 'RŒL¹9IÇ´Sþíba¤œIÎg;|xÄdÚfifݼK82ºˆŽßu2Þ'ÅHÔ|")Üÿ¬)8ÿ ldÉ0KØô†ÑŒvÁth[¾-ºº†9|ð-Ç”1ÃpêÊKòF ᱜ‡È”qã ˈ3¤F)SL³¥«µØÄ˜›$(È5®«0ÅŒÒVKñü„mRî`*%^æk<Ò¬“ sÔ˜ŒºÓëw˜«W'4ñ8&­þ1¬b¨²1µ;ï‚Ø½hô" B!…’9.ií‡mßê1.Ø·ê,ÿ£ÅñÞªk<,· ‡,ÊîplB Jt¶Eð±ÉÿØÊÊôµÎ#(‡„ÄV¤ @¤¦Üâ’r ­4ì Š;Vpåp*ÓÜ’÷µ†<1³,Qò8î s^É >½¾Çœ½Æ²zŒ|bÌ«zÁŒ!è/ŒHÛñ(­ÐyŽ˜<ÿÁÁ­y½PdO}Ìù¹òóáÞÚ&@Кet«+ÅʈÈõ×BO“\FÃ÷íký¡¡þÓÙÅÉN‚”dȯ=Mª„I”×B”÷4 B™âºlÉùûuê²|Õªç˜ík?b3Ôç:êå6žÉÍ?5$[Š;Y¶‘~óöȵ#˜FÔå±Ò"ŒSePÇ ¨:\…½DÉë¯oº’„à(1Iû*þÐH^öç£O6¿«üúiN59¡4ÅÅ”·ÏÃïdÚ®‰%EUÁ_ú% qgãËib h¨o¨¨h"ô0œ_ÒÈG¶Éå°pe+DíbéxR4¢,HÚ ŒÉùÚ-Qfƒù™¥ÅÇyÑñ“ã&QV|+6wÌkB7†’®Ix¾õÄ!”ûARßËrUðA`¯TÛÈÙ%è$é)¹M.„!aM]l2åÕɺ¹ÎXÿŒH]ü»§ÐÜÉþª.06yõ\,Ò¨#i‚ò w”JêL„9^Ùo5˜!žh°hžÙ°š—¨½ZAÏd¤_d)HÖH%2æ$ I`0™dNvùÿˆ¥Ø ˆêS-unWvF³0Ž«"‰Å$=2aD¬¯æ2™˜3yÒA´”z]?ÅÊ6„XÆa'—ÉWc„ÃQOöHEá s\ÉCíE:5>"“ërÙU+ôèèβ‘b^ƒC®QÿuÁ=í§ †øwry°ç¤@{ùiËæòÚ¶f§ŽÁ÷.J®Ä¶]f’ÃG>\tÂÖ»qžg‹E 9Fäf íd Ý›5h·ŽBМyÀ‡Ý½Q[tg‚°;¢8 ûuná ª§æF×·¦ë|º ¨9ÕJz¹`Û'.×½ZŒá*kÁ.@¸áÚ£æqQiv¡åê—ÓõËðˆ:Å+=mÛæsnV­¶¥/°oV½0"…:<…™æäõOÒŸ@T>`¸FÙõ Ý,jI¸Ý'ÆôU²`ÜqÊ0aªFµ”Ÿ7tªºtj-áëLÇk–Æmuˆˆ*!ÊùüάC˜•×-Ý5(=IËW¿nqYÕ çÙœ“lÔ{„·­#Ï¡ ¯k¹J†#„ø´”ê”.%L§'¼ ɹV©³ůÕ=ºsY9‡²pÇý²À<ÑbN`7ø¼ž¾S…:–JLínQý–ͪìõž¢–:rªÑ|L‘-â¡îöóŠÜâéãiÈΔÍÕÀÍå&"Ž 㸊 =ùíA§‘7`—ZkQ¼èÚ°-òj`–ò  a/zÔëj†‹^šËø™î¢G.£¹`sÉ=.L¤¥ÌŸŒ@á6 Ëhn—½çýŒŒ¢ÝX„Ó0?Ê–©é÷&Z¾¯Î@{@’‚•Ùt¸0XT֔ůœçé®lƒM‰qµs†Â»³)ct}0®ëpÙœ{c–k=ǃó?Êˋ£cºTû9¿Á̸égTayƒV-ÎìŽ t ¦&¥b̯çœZ•øjñ ¯DÒ²DRƒ›¼­âp÷‰pý¢Œ9··0ãÖX©¨íî SýȪDèÂÓQþtÁV¸ÑãÄd.b14öKºw°wüóËàSÝuŠ.¾ ô`ZébT¯x.¶1ŵ®±ˆï T«†¨ °ªw¼š¨J@ÛQDG¯G›J‰<£¼!Šj‹"ºZݳ¸R‚Uç©o˜àŠ“”ÜÕ™G%E)†à³ÂŽ ¤Ub¼ô§]•¨âcãé0£4âj «)¹Es¯®å¦(Û豂n™”];ö9=¾ÔRœcÚ2»´È‡×´C…ʘsݳþ˜ÓÛ\‘qÇ¿ŠG#U—ïmEMÛXFÉÅEÌô©-«¬ów¿CœNwTÍØt”wTÃr•G:ÔâX§àåXï æcW"\j·¸ëêPõY8[øÛ\uía_tåðPbÁ¦&r¸œà„}lñÂñjÁ GÃÉZ¢ä§GÉM_ÍŒ2¤Ë£zrEºâ‚Ë®¯¼1Gð¨Q+QTšßÛÀzéÑ£ÆF»LQáÓwÜCú†½ +Ç»ÅáJÈ¡:þwÂã, º1%è)Oç5ŠCCéŽNVï9sîáê\`sٌڦ.›«nL¿çh7ï’®$lTF•§ÄhûF%˜ßcGâ¨Cf9¬X¢Ô¬”¨çÆÉ´Þ¨ÒÝ‘7—!I‡¤3f´á(…pw]‡lÙª{ÔˆŽR[Që®Ú"DëB×Çvµ† ƒo°œ¶7¦íàÞØ%s.ˆ¹vqÅçƒpÙây`£ÙQ|ˆÓ¹Ä)1¢H§8%•–ÚSœòù Ë)NGví%NIö§$UÆ-=©º&ðy»zé!M©x²´Ûµm•’©Íç[ vHïdaJ?Ú¼¤éÒôj°¥) ò”¦dc‚ÚOiÊŒÎniÊŠüí™-MYñ,iJžÔo³.iJUP*—4uâ5ßÒÔEËé)M©s®kKÓN¹ôCœnø!O¯[ ’e*õ¨ýŒ”_•ÔÏê·íÃ/¢nXwc·èÂŒ]þ{JTÒ¾­Ýu„ýþ¨£ùqÎ%RGz¶S¤nø!R¯[¤Ìâr‹ÔÑv†ñ©­³­[`’dvú‚/±}aŽHºl‘:Šk]"uà¨Õ§H‘þ ©:Îüè–ª~HÕ«Å–™Œ™R–¼t<Ó¼19èjKÕQ£ºó”ª£ŽKk‡TaÎ_2s´ôAÊŽ(@HÕ±ë?O©zŠ€OBâç6ÈänxW/kæ(Ôn£ñá‹°;=ãeI¤,•d aÓíêþy¿üÔ¹‘)4¾^’wHïO sUAñ¨²ópÀN8–½úæR*¹…Ãõû4j¶d+ˆ9úµ[Kñ¯Jù@Û•gh¤Xúyêt[n~±+—›ÀÛˆ(j[‘Ù•7#Ý&å¯ZBî=Ê&¿ök8õ‰6Íõf±ö?4”ƒÙ=ž§ÊŒózjð³ƒmM.ø™)#"6 ¹Y\§—š«ñÒ*j@?wCÖt|**+{Þqø?3R¤øN€ ÔÇð·ñÄùYÚ5„0ýŽ…b‡ëý´ï‡\€£ç_ú%žƒÖVàYó÷gFŠ¥?Á÷ÒýòaÅköqð‰ûpÐlh’à¬Ô—?ˆ0x6é‘|îDÔ–/Üt×E3óñƉr?¹ç|ÑOýRdÖâS/N‡¸bªñ>msøÕmÿŒ§Œb>¾@£îú”vd«¿_qDºÈXÁðßÍI°Ÿ“d¶Ò!ÿ©[~lLž‡yC®íáâa½nO7Âì|ù)ÑaµAŒ¯zåï†mÿ·|ä°”òßñKP>»ÃŽtS5ìþ5¢Òe÷°j±¿íª+¬ zd?¡¼áÒ®9ÃÛ²ùÒêóùÓWX/êeƒ§•H>8§êZðV]õCr4G<î âî3£ç;Ì5÷Õë Æ/æóGÌáZ—Il“¨Fö[J'¸Çˆ8ÉŽ“G*¤‘Ãp¢[¬8[—o}\°óòEÝ-âý³a²”JLB+é¬"A®û.H©Ð¢ÏkN'æ‡Uuã]×NÌŸ0xc#> “–kF|Ùh=žgj<®ÑŸF K^S|Êßðšó¦¸ò>êY’M¥þ“`—5’Nô—y›¨wIH©±ŠiÑŹ>Øà#£Ø #Úî·«Ëõ¿˜áèõ¾<)jßb¢×¯/ã<0Nã=æ!¤æ5Ì7wú2Š]#‚ |‚çâ÷‚¾Êã¢'¿c•¢EHïr”a—(m‰`-F|ˆ ó'mFÞ"bî—0qGÒP~Ú÷.½"œç/x3”tÂÀ°;¤/FOØÕi»C Z<1=Èk°§ˆT÷Øk(Ã)¤kÕÏ~®]ðqÄ¢ö> ²b;Ÿç@’o>NŠll9öY樳¼ÎÚUæÜ·±az,j¤®¼&EBÔc/ú𢯋‰k5Õè±Y ~삨‘™qï³f{6×9Ôìoa=NªF©Åu–5÷ˆ¦î³¾á}bßÖ5À¾ÍkŠë¾¯EA\kÜô²7qԹ˓äÎS8Iò<§›hÏ“¼È:ú¢ú|á®&j¼-õ÷9 ñ;ß^`xÚ+ó1Ç¢ª³%\¨j‘j`ì½µæ|q¤ÁOê¥:˜ÕÈ3¶t^)†?Ùó¾¯Ú%3Ù÷•ý&+ñÂlǪù60ß²°˜Žp9IÀÝÁ¯fF¤# ÙÄÓ èòçvnŒ?_-ü¡023H@-Kß¡ŠìÊÞÆbKºÉŒ¿Ý7ùznÂLÎlµ³(DhýZÅÏ,ãœøp`i× „¶„qÁwØ=€‹ð ˇ£7l~ô§î£íVA¥D¬Ás¬-%âÀUêWäÝE6­FzÄïà{‹5!$ª¿šÓ „ˆˆø£`õ;L­»ú³pÕ:…ÆkDΓüÁ4\bžX6Þo 9\àÞ0éYØtz¶C"ÇE=àÍÅ>ÞÝ¢ÖHa0¥CbÝßëidŽÑ  Ôj~.AŸ©8+y–ëæõ|;ÂsJôXŠg(™—½Ë9ç°!/x„b¼ë`¼dêïïøcã0ŽÕh;IÄŠCÚN ©~’Ôö‰aÝFð¶ö«óÊåð— ‚JC(ñHÔtÊgÏ’YÏš~=Á33uc"ës¤™Óä‡Ú…²«ÈÔ·æ§w™üe ¿³}²_"óÂÓfV:Ó!ìb]_úX1¤oñ„ùòNœÓ…±£™yÿço«æײⳤoãm8SD‚×òœ¢Gñb?Àñ›ã­ÅíÁðE‚Ý>-UóCL”cßh·Ç\Žøt¥|j5 ßÿ¡`%Ïó»,Go‘§Ä—ÃLËì_ß#;z GòOŒàû¤ß“K±ÈµK7Š¿ê…ZÎÁ>¨…”÷æ>Ÿž_Êý½†¾¿ß³Þ鱇ó>ŸBй?Ü]¢ƒ%aŸ.L¦úÄ_íÖéyíq­½ú)¯Ü¢†ƒ†ÐÜêkæà¦mLlyU#„€m9,d­¬ÎŽü€±ÏfôLYŽ„{*°ê½¦e+TØè¹w/-ôÛ°$öl,Ló-®d·ã g2gXeñ†‰*ÓcÆŒ<;Xá¬zE¼T!€ÚöŠ#?¥Sßa㣅R{+pËôíZ‰Ð‡gµÚéTUcÛ´ÝÚÓÏ\¡²â7Þç‘NЧP"رç} »›eDZ+Ú?K³Xtys³y†¤K.^mõƺá±'zœ˜äèD^9jw*_J³¶KÖ®¶§¶¾ÛÀˆ°ò·@$hµ"µy–*<¬:…§çÓ­QæÂ‡âÛ9G²V3ÅRq¤¶d ¯é†ëÎÍܘø<¥ŸÃ÷0 {Hkï¡öýM†ã‚ ÁUB¼s°”bó¾‹%®Þ{åÂøî1C2×Ü\:ÿóÇS6EE°‡\¥¯fµà’6wÈiEiw«ñ6ÄÒØ=zSå‚ËÉW&¶æƒ÷?Jdé?ÿø?gµendstream endobj 6 0 obj 9338 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:09:56+10:00 2013-08-12T12:09:56+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/point_cloud.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000009642 00000 n 0000011320 00000 n 0000009583 00000 n 0000009443 00000 n 0000000015 00000 n 0000009423 00000 n 0000009706 00000 n 0000009747 00000 n 0000009776 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [] >> startxref 11562 %%EOF opengv/doc/addons/images/reprojectionError.eps0000664016516101651610000005740413344612246020531 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/reprojectionError.dia %%Creator: Dia v0.97.2 %%CreationDate: Tue Aug 13 10:20:48 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 513 330 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -29.435459 -28.232726 translate %%EndProlog 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 38.197263 16.964842 m 30.034066 16.964842 l s [] 0 sd 0 slj 0 slc n 29.659066 16.964842 m 30.159066 16.714842 l 30.034066 16.964842 l 30.159066 17.214842 l ef n 29.659066 16.964842 m 30.159066 16.714842 l 30.034066 16.964842 l 30.159066 17.214842 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 38.150000 16.950000 m 32.598625 22.360238 l s [] 0 sd 0 slj 0 slc n 32.330068 22.621967 m 32.513658 22.093957 l 32.598625 22.360238 l 32.862630 22.452033 l ef n 32.330068 22.621967 m 32.513658 22.093957 l 32.598625 22.360238 l 32.862630 22.452033 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 38.152737 16.917579 m 38.156775 24.092345 l s [] 0 sd 0 slj 0 slc n 38.156986 24.467344 m 37.906705 23.967485 l 38.156775 24.092345 l 38.406705 23.967204 l ef n 38.156986 24.467344 m 37.906705 23.967485 l 38.156775 24.092345 l 38.406705 23.967204 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 38.189470 16.992646 m 44.718080 26.288143 l s [] 0 sd 0 slj 0 slc n 44.933611 26.595017 m 44.441654 26.329539 l 44.718080 26.288143 l 44.850820 26.042165 l ef n 44.933611 26.595017 m 44.441654 26.329539 l 44.718080 26.288143 l 44.850820 26.042165 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slj 0 slc 0.000000 0.882353 0.894118 srgb n 44.511555 22.731154 m 46.197444 22.763575 43.506506 25.357251 41.853037 25.324830 c 40.199569 25.292409 42.825666 22.698733 44.511555 22.731154 c s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 41.366723 25.195146 m 38.157049 16.960225 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.030290 22.893258 m 38.124628 16.992646 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.572549 0.000000 0.000000 srgb n 38.155452 17.000775 m 43.470848 26.905984 l s [] 0 sd 0 slj 0 slc n 43.648166 27.236413 m 43.191456 26.914052 l 43.470848 26.905984 l 43.632029 26.677629 l ef n 43.648166 27.236413 m 43.191456 26.914052 l 43.470848 26.905984 l 43.632029 26.677629 l cp s 0.000000 0.000000 0.000000 srgb 1.000000 0.000000 0.000000 srgb gsave 45.218332 26.084337 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 45.665595 26.359337 translate 0.035278 -0.035278 scale start_ol 1017 2758 moveto 1104 2808 1223 2864 conicto 1343 2920 1470 2966 conicto 1598 3013 1729 3042 conicto 1860 3072 1972 3072 conicto 2186 3072 2368 2991 conicto 2550 2910 2640 2732 conicto 2739 2788 2879 2849 conicto 3019 2910 3170 2960 conicto 3321 3010 3468 3041 conicto 3616 3072 3734 3072 conicto 3902 3072 4038 3025 conicto 4175 2978 4273 2874 conicto 4371 2770 4425 2603 conicto 4480 2436 4480 2200 conicto 4480 256 lineto 4866 165 lineto 4866 0 lineto 3522 0 lineto 3522 165 lineto 3968 256 lineto 3968 2146 lineto 3968 2408 3851 2548 conicto 3735 2688 3470 2688 conicto 3390 2688 3282 2675 conicto 3175 2662 3067 2646 conicto 2960 2630 2862 2609 conicto 2764 2589 2697 2576 conicto 2752 2406 2752 2201 conicto 2752 256 lineto 3201 165 lineto 3201 0 lineto 1797 0 lineto 1797 165 lineto 2240 256 lineto 2240 2146 lineto 2240 2408 2107 2548 conicto 1974 2688 1709 2688 conicto 1621 2688 1525 2678 conicto 1430 2669 1338 2656 conicto 1246 2643 1163 2625 conicto 1080 2608 1024 2595 conicto 1024 256 lineto 1473 165 lineto 1473 0 lineto 133 0 lineto 133 165 lineto 512 256 lineto 512 2752 lineto 133 2843 lineto 133 3008 lineto 992 3008 lineto 1017 2758 lineto end_ol grestore gsave 46.337463 26.359337 translate 0.035278 -0.035278 scale start_ol 832 1472 moveto 832 1416 lineto 832 1188 864 978 conicto 897 769 993 608 conicto 1090 447 1265 351 conicto 1441 256 1727 256 conicto 1819 256 1920 264 conicto 2022 272 2123 284 conicto 2225 297 2320 313 conicto 2416 329 2496 348 conicto 2496 173 lineto 2425 127 2324 85 conicto 2223 44 2101 10 conicto 1980 -24 1843 -44 conicto 1707 -64 1567 -64 conicto 1204 -64 953 38 conicto 703 140 548 340 conicto 393 541 324 837 conicto 256 1133 256 1518 conicto 256 2302 578 2687 conicto 900 3072 1496 3072 conicto 1731 3072 1935 3007 conicto 2140 2942 2293 2789 conicto 2446 2636 2535 2379 conicto 2624 2122 2624 1739 conicto 2624 1472 lineto 832 1472 lineto 1485 2816 moveto 1317 2816 1195 2739 conicto 1073 2662 993 2521 conicto 913 2380 875 2178 conicto 838 1977 838 1728 conicto 2048 1728 lineto 2048 1977 2022 2178 conicto 1997 2380 1932 2521 conicto 1867 2662 1759 2739 conicto 1651 2816 1485 2816 conicto end_ol grestore gsave 46.722101 26.359337 translate 0.035278 -0.035278 scale start_ol 1482 3072 moveto 1685 3072 1860 3034 conicto 2035 2996 2162 2904 conicto 2289 2813 2360 2656 conicto 2432 2500 2432 2263 conicto 2432 256 lineto 2805 165 lineto 2805 0 lineto 1998 0 lineto 1939 300 lineto 1892 252 1811 188 conicto 1730 124 1616 68 conicto 1502 13 1352 -25 conicto 1202 -64 1018 -64 conicto 803 -64 656 2 conicto 509 68 420 186 conicto 332 304 294 466 conicto 256 629 256 818 conicto 256 1013 303 1156 conicto 351 1300 436 1397 conicto 522 1495 637 1556 conicto 753 1618 887 1652 conicto 1022 1687 1172 1699 conicto 1322 1712 1474 1715 conicto 1920 1728 lineto 1920 2204 lineto 1920 2340 1897 2451 conicto 1875 2563 1822 2644 conicto 1769 2725 1679 2770 conicto 1589 2816 1454 2816 conicto 1299 2816 1141 2775 conicto 984 2735 865 2669 conicto 756 2304 lineto 576 2304 lineto 576 2960 lineto 783 3005 1003 3038 conicto 1224 3072 1482 3072 conicto 1920 1472 moveto 1501 1459 lineto 1312 1453 1174 1423 conicto 1037 1394 947 1322 conicto 858 1250 813 1125 conicto 768 1000 768 806 conicto 768 256 1226 256 conicto 1443 256 1601 305 conicto 1760 355 1920 431 conicto 1920 1472 lineto end_ol grestore gsave 47.106739 26.359337 translate 0.035278 -0.035278 scale start_ol 2304 840 moveto 2304 640 2241 472 conicto 2179 305 2044 186 conicto 1909 67 1695 1 conicto 1481 -64 1179 -64 conicto 1028 -64 881 -46 conicto 735 -29 609 -4 conicto 484 20 391 45 conicto 298 71 256 87 conicto 256 832 lineto 399 832 lineto 555 411 lineto 654 321 809 256 conicto 965 192 1175 192 conicto 1471 192 1631 320 conicto 1792 448 1792 716 conicto 1792 875 1725 978 conicto 1659 1082 1551 1152 conicto 1444 1222 1306 1268 conicto 1168 1315 1024 1362 conicto 880 1410 742 1470 conicto 604 1531 496 1626 conicto 389 1722 322 1865 conicto 256 2009 256 2222 conicto 256 2426 331 2585 conicto 406 2744 540 2852 conicto 675 2961 862 3016 conicto 1049 3072 1273 3072 conicto 1494 3072 1705 3041 conicto 1917 3010 2112 2971 conicto 2112 2304 lineto 1962 2304 lineto 1829 2662 lineto 1746 2737 1602 2776 conicto 1459 2816 1297 2816 conicto 1039 2816 903 2689 conicto 768 2562 768 2346 conicto 768 2200 834 2106 conicto 900 2012 1008 1946 conicto 1116 1881 1254 1833 conicto 1392 1786 1536 1735 conicto 1680 1684 1818 1618 conicto 1956 1553 2064 1451 conicto 2172 1350 2238 1203 conicto 2304 1057 2304 840 conicto end_ol grestore 0.572549 0.000000 0.000000 srgb gsave 42.235604 27.770226 translate 0.035278 -0.035278 scale start_ol 832 4416 moveto 82 4416 lineto 82 4798 lineto 832 5014 lineto 832 5542 lineto 832 6059 969 6448 conicto 1107 6837 1363 7096 conicto 1619 7355 1991 7485 conicto 2364 7616 2835 7616 conicto 2951 7616 3075 7608 conicto 3199 7600 3318 7587 conicto 3437 7574 3537 7555 conicto 3638 7537 3712 7516 conicto 3712 6336 lineto 3374 6336 lineto 3222 6913 lineto 3175 6961 3093 7000 conicto 3012 7040 2892 7040 conicto 2777 7040 2680 6969 conicto 2583 6899 2515 6739 conicto 2447 6580 2407 6326 conicto 2368 6073 2368 5708 conicto 2368 4992 lineto 3392 4992 lineto 3392 4416 lineto 2368 4416 lineto 2368 448 lineto 3176 329 lineto 3176 0 lineto 293 0 lineto 293 329 lineto 832 448 lineto 832 4416 lineto end_ol grestore gsave 42.682867 28.045226 translate 0.035278 -0.035278 scale start_ol 2112 3072 moveto 2112 2240 lineto 1974 2240 lineto 1787 2613 lineto 1697 2613 1594 2600 conicto 1491 2588 1388 2567 conicto 1285 2547 1190 2519 conicto 1095 2491 1024 2459 conicto 1024 256 lineto 1537 165 lineto 1537 0 lineto 133 0 lineto 133 165 lineto 512 256 lineto 512 2752 lineto 133 2843 lineto 133 3008 lineto 990 3008 lineto 1018 2619 lineto 1092 2680 1220 2758 conicto 1349 2836 1499 2906 conicto 1649 2976 1798 3024 conicto 1948 3072 2064 3072 conicto 2112 3072 lineto end_ol grestore gsave 42.970097 28.045226 translate 0.035278 -0.035278 scale start_ol 832 1472 moveto 832 1416 lineto 832 1188 864 978 conicto 897 769 993 608 conicto 1090 447 1265 351 conicto 1441 256 1727 256 conicto 1819 256 1920 264 conicto 2022 272 2123 284 conicto 2225 297 2320 313 conicto 2416 329 2496 348 conicto 2496 173 lineto 2425 127 2324 85 conicto 2223 44 2101 10 conicto 1980 -24 1843 -44 conicto 1707 -64 1567 -64 conicto 1204 -64 953 38 conicto 703 140 548 340 conicto 393 541 324 837 conicto 256 1133 256 1518 conicto 256 2302 578 2687 conicto 900 3072 1496 3072 conicto 1731 3072 1935 3007 conicto 2140 2942 2293 2789 conicto 2446 2636 2535 2379 conicto 2624 2122 2624 1739 conicto 2624 1472 lineto 832 1472 lineto 1485 2816 moveto 1317 2816 1195 2739 conicto 1073 2662 993 2521 conicto 913 2380 875 2178 conicto 838 1977 838 1728 conicto 2048 1728 lineto 2048 1977 2022 2178 conicto 1997 2380 1932 2521 conicto 1867 2662 1759 2739 conicto 1651 2816 1485 2816 conicto end_ol grestore gsave 43.354735 28.045226 translate 0.035278 -0.035278 scale start_ol 512 2752 moveto 170 2843 lineto 170 3008 lineto 999 3008 lineto 1005 2817 lineto 1071 2874 1161 2920 conicto 1252 2967 1356 3000 conicto 1461 3034 1578 3053 conicto 1695 3072 1815 3072 conicto 2094 3072 2315 2973 conicto 2537 2875 2692 2679 conicto 2847 2483 2927 2195 conicto 3008 1907 3008 1531 conicto 3008 1165 2925 870 conicto 2843 576 2678 367 conicto 2514 159 2266 47 conicto 2018 -64 1685 -64 conicto 1524 -64 1345 -46 conicto 1166 -29 1005 6 conicto 1008 -32 1013 -81 conicto 1018 -130 1019 -182 conicto 1021 -234 1022 -278 conicto 1024 -323 1024 -351 conicto 1024 -1152 lineto 1547 -1239 lineto 1547 -1408 lineto 132 -1408 lineto 132 -1239 lineto 512 -1152 lineto 512 2752 lineto 2432 1541 moveto 2432 1867 2378 2097 conicto 2325 2327 2222 2472 conicto 2120 2618 1972 2685 conicto 1824 2752 1638 2752 conicto 1487 2752 1315 2725 conicto 1144 2698 1024 2647 conicto 1024 246 lineto 1156 221 1317 206 conicto 1478 192 1638 192 conicto 2054 192 2243 542 conicto 2432 892 2432 1541 conicto end_ol grestore gsave 43.786825 28.045226 translate 0.035278 -0.035278 scale start_ol 2112 3072 moveto 2112 2240 lineto 1974 2240 lineto 1787 2613 lineto 1697 2613 1594 2600 conicto 1491 2588 1388 2567 conicto 1285 2547 1190 2519 conicto 1095 2491 1024 2459 conicto 1024 256 lineto 1537 165 lineto 1537 0 lineto 133 0 lineto 133 165 lineto 512 256 lineto 512 2752 lineto 133 2843 lineto 133 3008 lineto 990 3008 lineto 1018 2619 lineto 1092 2680 1220 2758 conicto 1349 2836 1499 2906 conicto 1649 2976 1798 3024 conicto 1948 3072 2064 3072 conicto 2112 3072 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slj 0 slc 0.000000 0.000000 0.000000 srgb n 43.248609 26.397600 m 43.793861 26.206761 44.025241 26.070511 44.284608 25.681460 c s gsave 42.959182 25.811338 translate 0.035278 -0.035278 scale start_ol 3895 1611 moveto 3101 -128 1854 -128 conicto 1194 -128 821 392 conicto 448 913 448 1849 conicto 448 3340 1381 4614 conicto 2315 5888 3692 5888 conicto 4373 5888 4905 5597 conicto 5169 5745 lineto 5423 5888 5444 5888 conicto 5824 5888 lineto 4330 -1170 lineto 4267 -1472 4267 -1657 conicto 4267 -2170 5011 -2170 conicto 5101 -2170 lineto 5001 -2624 lineto 3031 -2624 lineto 3486 -456 lineto 3528 -250 3964 1611 conicto 3895 1611 lineto 4578 5010 moveto 4339 5402 3754 5402 conicto 2812 5402 2187 4207 conicto 1562 3012 1562 1796 conicto 1562 553 2250 553 conicto 2788 553 3379 1338 conicto 3971 2124 4177 3097 conicto 4578 5010 lineto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 43.428923 21.194033 translate 0.035278 -0.035278 scale start_ol 3895 1611 moveto 3101 -128 1854 -128 conicto 1194 -128 821 392 conicto 448 913 448 1849 conicto 448 3340 1381 4614 conicto 2315 5888 3692 5888 conicto 4373 5888 4905 5597 conicto 5169 5745 lineto 5423 5888 5444 5888 conicto 5824 5888 lineto 4330 -1170 lineto 4267 -1472 4267 -1657 conicto 4267 -2170 5011 -2170 conicto 5101 -2170 lineto 5001 -2624 lineto 3031 -2624 lineto 3486 -456 lineto 3528 -250 3964 1611 conicto 3895 1611 lineto 4578 5010 moveto 4339 5402 3754 5402 conicto 2812 5402 2187 4207 conicto 1562 3012 1562 1796 conicto 1562 553 2250 553 conicto 2788 553 3379 1338 conicto 3971 2124 4177 3097 conicto 4578 5010 lineto end_ol grestore gsave 44.304289 21.349794 translate 0.035278 -0.035278 scale start_ol 1068 -64 moveto 756 -64 602 119 conicto 448 302 448 634 conicto 448 2752 lineto 56 2752 lineto 56 2889 lineto 454 3008 lineto 766 3712 lineto 960 3712 lineto 960 3008 lineto 1645 3008 lineto 1645 2752 lineto 960 2752 lineto 960 680 lineto 960 469 1059 362 conicto 1158 256 1319 256 conicto 1443 256 1565 272 conicto 1688 288 1792 307 conicto 1792 112 lineto 1743 80 1663 48 conicto 1584 16 1488 -8 conicto 1393 -32 1285 -48 conicto 1178 -64 1068 -64 conicto end_ol grestore gsave 44.544059 21.349794 translate 0.035278 -0.035278 scale start_ol 1024 3233 moveto 1024 3188 1022 3123 conicto 1021 3059 1019 2990 conicto 1018 2921 1013 2856 conicto 1008 2792 1002 2750 conicto 1092 2801 1220 2858 conicto 1349 2916 1489 2963 conicto 1629 3011 1769 3041 conicto 1909 3072 2025 3072 conicto 2198 3072 2343 3025 conicto 2488 2978 2592 2874 conicto 2697 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1906 0 lineto 1906 165 lineto 2304 256 lineto 2304 2150 lineto 2304 2410 2171 2549 conicto 2039 2688 1761 2688 conicto 1669 2688 1566 2679 conicto 1463 2671 1361 2660 conicto 1260 2649 1171 2633 conicto 1083 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 133 0 lineto 133 165 lineto 512 256 lineto 512 4288 lineto 66 4377 lineto 66 4544 lineto 1024 4544 lineto 1024 3233 lineto end_ol grestore gsave 44.976149 21.349794 translate 0.035278 -0.035278 scale start_ol 2112 3072 moveto 2112 2240 lineto 1974 2240 lineto 1787 2613 lineto 1697 2613 1594 2600 conicto 1491 2588 1388 2567 conicto 1285 2547 1190 2519 conicto 1095 2491 1024 2459 conicto 1024 256 lineto 1537 165 lineto 1537 0 lineto 133 0 lineto 133 165 lineto 512 256 lineto 512 2752 lineto 133 2843 lineto 133 3008 lineto 990 3008 lineto 1018 2619 lineto 1092 2680 1220 2758 conicto 1349 2836 1499 2906 conicto 1649 2976 1798 3024 conicto 1948 3072 2064 3072 conicto 2112 3072 lineto end_ol grestore gsave 45.263379 21.349794 translate 0.035278 -0.035278 scale start_ol 832 1472 moveto 832 1416 lineto 832 1188 864 978 conicto 897 769 993 608 conicto 1090 447 1265 351 conicto 1441 256 1727 256 conicto 1819 256 1920 264 conicto 2022 272 2123 284 conicto 2225 297 2320 313 conicto 2416 329 2496 348 conicto 2496 173 lineto 2425 127 2324 85 conicto 2223 44 2101 10 conicto 1980 -24 1843 -44 conicto 1707 -64 1567 -64 conicto 1204 -64 953 38 conicto 703 140 548 340 conicto 393 541 324 837 conicto 256 1133 256 1518 conicto 256 2302 578 2687 conicto 900 3072 1496 3072 conicto 1731 3072 1935 3007 conicto 2140 2942 2293 2789 conicto 2446 2636 2535 2379 conicto 2624 2122 2624 1739 conicto 2624 1472 lineto 832 1472 lineto 1485 2816 moveto 1317 2816 1195 2739 conicto 1073 2662 993 2521 conicto 913 2380 875 2178 conicto 838 1977 838 1728 conicto 2048 1728 lineto 2048 1977 2022 2178 conicto 1997 2380 1932 2521 conicto 1867 2662 1759 2739 conicto 1651 2816 1485 2816 conicto end_ol grestore gsave 45.648017 21.349794 translate 0.035278 -0.035278 scale start_ol 2304 840 moveto 2304 640 2241 472 conicto 2179 305 2044 186 conicto 1909 67 1695 1 conicto 1481 -64 1179 -64 conicto 1028 -64 881 -46 conicto 735 -29 609 -4 conicto 484 20 391 45 conicto 298 71 256 87 conicto 256 832 lineto 399 832 lineto 555 411 lineto 654 321 809 256 conicto 965 192 1175 192 conicto 1471 192 1631 320 conicto 1792 448 1792 716 conicto 1792 875 1725 978 conicto 1659 1082 1551 1152 conicto 1444 1222 1306 1268 conicto 1168 1315 1024 1362 conicto 880 1410 742 1470 conicto 604 1531 496 1626 conicto 389 1722 322 1865 conicto 256 2009 256 2222 conicto 256 2426 331 2585 conicto 406 2744 540 2852 conicto 675 2961 862 3016 conicto 1049 3072 1273 3072 conicto 1494 3072 1705 3041 conicto 1917 3010 2112 2971 conicto 2112 2304 lineto 1962 2304 lineto 1829 2662 lineto 1746 2737 1602 2776 conicto 1459 2816 1297 2816 conicto 1039 2816 903 2689 conicto 768 2562 768 2346 conicto 768 2200 834 2106 conicto 900 2012 1008 1946 conicto 1116 1881 1254 1833 conicto 1392 1786 1536 1735 conicto 1680 1684 1818 1618 conicto 1956 1553 2064 1451 conicto 2172 1350 2238 1203 conicto 2304 1057 2304 840 conicto end_ol grestore gsave 45.985195 21.349794 translate 0.035278 -0.035278 scale start_ol 1024 3233 moveto 1024 3188 1022 3123 conicto 1021 3059 1019 2990 conicto 1018 2921 1013 2856 conicto 1008 2792 1002 2750 conicto 1092 2801 1220 2858 conicto 1349 2916 1489 2963 conicto 1629 3011 1769 3041 conicto 1909 3072 2025 3072 conicto 2198 3072 2343 3025 conicto 2488 2978 2592 2874 conicto 2697 2770 2756 2603 conicto 2816 2436 2816 2200 conicto 2816 256 lineto 3179 165 lineto 3179 0 lineto 1906 0 lineto 1906 165 lineto 2304 256 lineto 2304 2150 lineto 2304 2410 2171 2549 conicto 2039 2688 1761 2688 conicto 1669 2688 1566 2679 conicto 1463 2671 1361 2660 conicto 1260 2649 1171 2633 conicto 1083 2618 1024 2607 conicto 1024 256 lineto 1429 165 lineto 1429 0 lineto 133 0 lineto 133 165 lineto 512 256 lineto 512 4288 lineto 66 4377 lineto 66 4544 lineto 1024 4544 lineto 1024 3233 lineto end_ol grestore gsave 46.417285 21.349794 translate 0.035278 -0.035278 scale start_ol 3008 1512 moveto 3008 751 2669 343 conicto 2330 -64 1613 -64 conicto 941 -64 598 340 conicto 256 745 256 1512 conicto 256 2270 598 2671 conicto 941 3072 1638 3072 conicto 2317 3072 2662 2679 conicto 3008 2286 3008 1512 conicto 2432 1514 moveto 2432 1822 2391 2065 conicto 2350 2308 2254 2474 conicto 2158 2641 2000 2728 conicto 1843 2816 1613 2816 conicto 1380 2816 1229 2728 conicto 1078 2641 989 2474 conicto 901 2308 866 2065 conicto 832 1822 832 1514 conicto 832 1202 866 957 conicto 901 713 989 543 conicto 1078 373 1229 282 conicto 1380 192 1613 192 conicto 1843 192 2000 282 conicto 2158 373 2254 543 conicto 2350 713 2391 957 conicto 2432 1202 2432 1514 conicto end_ol grestore gsave 46.849374 21.349794 translate 0.035278 -0.035278 scale start_ol 1152 256 moveto 1665 165 lineto 1665 0 lineto 130 0 lineto 130 165 lineto 640 256 lineto 640 4288 lineto 130 4377 lineto 130 4544 lineto 1152 4544 lineto 1152 256 lineto end_ol grestore gsave 47.089144 21.349794 translate 0.035278 -0.035278 scale start_ol 2324 223 moveto 2184 111 1975 23 conicto 1766 -64 1483 -64 conicto 256 -64 256 1467 conicto 256 1840 337 2137 conicto 418 2435 587 2643 conicto 756 2852 1014 2962 conicto 1272 3072 1626 3072 conicto 1788 3072 1971 3053 conicto 2154 3034 2324 2999 conicto 2317 3034 2314 3101 conicto 2311 3169 2309 3246 conicto 2308 3323 2306 3398 conicto 2304 3474 2304 3521 conicto 2304 4288 lineto 1801 4377 lineto 1801 4544 lineto 2816 4544 lineto 2816 256 lineto 3185 165 lineto 3185 0 lineto 2361 0 lineto 2324 223 lineto 832 1464 moveto 832 1127 891 896 conicto 950 666 1058 523 conicto 1166 381 1318 318 conicto 1471 256 1659 256 conicto 1849 256 2017 296 conicto 2186 336 2304 392 conicto 2304 2762 lineto 2170 2787 1995 2801 conicto 1821 2816 1659 2816 conicto 1236 2816 1034 2473 conicto 832 2130 832 1464 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slj 0 slc n 42.171737 22.676256 m 42.714793 22.255156 42.948720 22.171898 43.453078 21.599383 c s showpage opengv/doc/addons/images/absolute_central.pdf0000664016516101651610000003435713344612246020326 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝ»’f;ŽýzŠ´e¤x¿ò,ŸeN5)ýsÔ:>{Í%Zõ¾jüñ#ºöUÔ-F.Ÿ«¾G.{~¦üQSÌ#ºkðVægŸ«ósið2ög)iL ^ûþlõ£ìsÚ}§ù‘ûΟeG'­¯Í$ü÷©ñZ›«w“QÒçÑd®˜}nw:ÁòsåVL?|hÔ>S`äX^±ÚL•µÅìWôQç¶â¿ç ºÅ,bàh54ADi3¾žSöúÿ}ó?ÿýGOÑiBâXsá›=µò¹çé©¶Ï‘Ã÷” x|Æ6ýŒñ¹±ÀìÏ;š¢å.²œ>ûl0=’ˆRGMŸ-Ö’Rì!=jÿ¬|3Å4l‰©üüÑv¬DÓlãs”€c;`¦ßßðö'nÌ º/v¢íYù¯?avýL`âÃùsÇÄVL –¦4¾PW°I¦ÞÄ^À<½‚)ëøæþúÝë;fŒhÛ¾`ºfp‡èA‡ùÙ&ð†Ä×Ïì͈¾‹uÁ˜GK‘:¶+kÎû†é,¬ ¾ZÄÉ ÎPìˆàáìô9‹?Pƒ7Sp­¶n‹çRìT߆ƒuÕá`JEˆñ¥aÅC$µÈgȤÃÊ)JcÅtÄ”ÁšVÐ^L©¹Ç–Y.˜r ¯Êû6r‡9NŸµ˜ðè¬Vpi¦\ö,8þ´èg–×AøzT~þø;2K«®3ÖÖ9Œ7fì'"Vâocü szýú6Î ³BÔúyÎÎ^¿Çù†9½¾ó‹YCçÒÞ‡^‡y?kE]‡>DR)ènbNk¤f6ËÚg¤¯d@ÈÜÞcÓG÷·MË_ÚT‘!àCäY.&\-@=’ǬâÁŽÜÓb©ñÀ!oÄ&fk÷q|4Âõ>a}ãÌ"6?<“Mçë^Fœ¢Z½ð³Ðà§â!D\[íE©`¿¸²èp‘26 ¹}“z±î½†éQkÞ-$ žjõ*ŸoÄéìïI…Ö{’!4â³ é³ÎÑÖY·È0zb^tBЖ‡ü›êCè¾¶âÁx³®Î^Þ_¸wûžÂá‡k†‡]î%Ü u/ò°ÜM„‹%/2=L{òâê‹Ð×="lÜ´à†h>)ÉÛg ',T$ÍDV£Ët¤TãîéËZ@Göê±!ƒ/-ɯôÞškÑ:c?r½¶43êŸEëÏÜQÇ §-Óí¡[Hô˜šÙ yž‡IÜa•÷Xëê3®ôù«1»h²"#©8ëÛêq0å0VŒ€¤^ålñFÔ„ÆÐNóèü™‹¼>l¶bo‹à.²¬˜êÅ—1Y[KTà:ZÁˆ-:q?sï=: é½ÎÜ›ÓVýEÃ:ÀS›s·ˆÅ^-$†¦‡G>ˆxYŸ‰?ÇE´4ã{ܽW˜qJ¹îV°•ŠÄc|ÇLm ˜!õ00ˆ©Ðª_ˆ5v24·Ð„=­í¬¤iÁ•ð:ðäð9ÀùÕ dŠC|9õ±tƒ G‡‚­h+Šöj0b¨héfITÚDÜ3M^à­¸›b_fÈÅ ‡«ÇQÛ­þ¨C耰HΈý; Àb'âÇ¡Ú(R1ã!=då%/‡IËDBÓG2ŽXÛT‹äOøÀÖ‰àØ_]°ÙÖõùÀõi£&”ç¢Û6¬`A”¦ß7…rÅ—šN“C¼‚ŸK‰)ĸàŸ?J©¨æ¯A¿PŸ _ß ÇÁ„(©qx®„Uã‚éáYÜ-®y_#üe?ïE†Uò¯»Èÿ³è_{u á‡0ןÁÅ¿_˜0k†Î{–°ž±™¹€c!Ï.øç’¾Òã`J¬ªÒãŒðÀþFÌõÆ„ÙÌ‘¿Fhq-rº®o8¾qÍâ`žYz„¿®ý×]Û¿öαºÜb`¡q6jÕ‰k€‹+úK­©µîMê€?ĆÌûó÷‚Vžî|>nLˆxQÑýQ€cž÷ÌÎ ®÷œ=À_–KþK.ë_v¿XX(C5ô–œQYñð­Ì+Ô‹À Ü]Áß%Tlà…‚„ÙVÞV(Q Jzhoø6rˆä€+:jNøK¡µ8'\ê!ßD=ofÉ3ù7T,ÁÕ(zÄéZ[cÊnÈq‚Ë(†CìgîPç.8z„¢ã>-ÂLky–¬x…^5˜UVGS7uz„"‡¼Ä,sJà{ ­óch…&ª° Jhpy§3Tê[Xp,H\°‡–Ô2d´×ŽÿæÐ¥ƒÄ;ö É@ÉpãɉÑFSakìqæÙ—„ÑŽ»²Èæd©5ºéª œF;Tu¢ Éµ „¨»ÿ *4P.ì‚0ºÆÀ@Ø…&›X/ãóŰ£bPZ`-ŒÏ7zî°$¼€•uö3…ö¸0/KÑ)>p«°LÇdhî&Î Lð!ìK…‰¶±å‚ß^)Ìœ­—³{`3l ï¢!w Ûm‡ÅÜÂöwî`×΀ØAÎÄÁ Œq¨/âæÉ?0ÄpaähÇ¥VA 3·Ï7f†u¿±ƒò‹%ýs÷ ë{i‘×À"˜rb†þL:3Lzøê_0q¼6¶ÓD¬õÂüõXǃ^œZü©Õì ‚›`á8y;L¬XHÂ$ædfñþñb2vƒGÓ–Ç5cÑnäD8erH™ÍëEÌ]ö ŸÖ͘óÄéÀt—‡°s,±6„@‘u‚È÷²}$%Ppð盈…±ø§È^òC¯8D,ß<:#ÌpÇù,G{xÌ Ò­‚«¨Þꀓ'u³¼*ãuóʰÒ^UR€—š$µâ[í†Y˜ò´¨ØÌC]r0xspð÷qÞŠú"v×Þ›…khüe3uõnüÕûë?-^2"Ä3;¹CŽ õ‚N;¶;ôk$úÒãÐ`]=]ÅØ@õ`ÿéÞåFÇL²³NùúÀ#!!·ÃRÝÁëT}q³éG¬5 ¿0µãЃYÈ—½ô6À›GØÀ¿`äkHâ`¡ ÿO¸ pyÀÞ…§š#ËM}£@\„¡ñ…9-Bòàí–§p?p\K®Ã¤Ø“ot{ôBqkƒgÞ¿ÎüàÂãSÑ&tk0Có’üdÓ¦ütˆå†\jA­:¸UŠî¼ÖÑA™aHáÊûXÚJhJÈåÀh³0üwÀñÏe¦Ð‹²Y“¸[ =@5.`Q6ämlbÃp6¯g|ù`øjF|.F’šb'fÙ–—!ÄÒߌ ¸=â€;B9ÈCÈZ„05èT·/àt›6Ã! ZP§ÊbL,38¬7zñò·¢`ÖÈu-õ^˜›'ƒt† þi8ÀR}àÌke½{àÞØÁFˆW1m—ï2(ÓߘQB¾IÚ/^”þ€xú¬¥ëü5îÁØÑzwŠåÉ5ÚúLÝ“gS¥ä}Á|9Ö¿àŽ†Àîò("ÉoL—ÈPnßÖø^(%ø÷8èsà †¶ôÑQ¬¦L=|aý ^öÖ®âûßg÷CnŽ\ýÁ§œÔ…b«¿܆MN¸jŽÄ/ç“É,uö׸é!Žå$XâDžó§¾càs)H Ñ-ÆûßäŠä«]ò ¿œžZ¹wÄõtÍéðú“\Yz¼MÇ–±qœý±…Fµv÷,S¿a­« Ã>-vH­ã^}Vuu5žçú2±³¸t÷íãÞ-ŽýšÝO sÞî¢w…µ§nkÞ(ñT+"`úšnj†˜yıßÊq KiÅ÷פnÆ,ƒuÐÛAæ½qëÕo ™7JÌ ÎãæÒÆ‹ ظô0Ð`P뎱/!(*º¡doÁÜöÜêµÝ0=‚ص¼ZŒ éNŸ28`FeÔcËZ[ð+[ІŽ7½N«7Üôˆ£Sô$’Q¸ñ™Ö<àø€«|ß#¨»GÒÊJp¸ÆŒCÝâJC~…ò²äU-³\+GØÆÊËàfcU¾ìÒqMÜ¥Í|^vbåE3†E)K¼hعbƒtšÜÓ!Ù~·½âCº´í:.m\û·ÌÁ'º¢Èƒ^üàü£Ò˜T:˃¼ð‚5Ü¢u žá¶†0¾N%LQœ 0ßâÚg¯B¦öñ×ÝD¢Wb³°ô„D¯ÈM¬q©¸h7&AÝ%s°èÎøæîUð„,¸F~09ÏÔÓI6OŠßó †×ho¾€¬ðMçLù;æùÔß$,‚…wѸPGöq}óëÁÌúé0¶Â8(#¶7”n\MoÖY0Çgh¾Iz7{²ƒW‚愨ÁÝÄ™%,(:ø•½%«át@VÚ+=;#ù>pÓÆ€ .iñ¡-WE‘?%®r½§†âŸ‡¶‘;3®uà†dàúÊrn0kÝI‹¨Dºù‰"cÅ'xÖƒ\!´!ùRP0C›{7¬w»»ÄyÚ3öóck„¡CÛ¶5MJïó=_À¬ôyÂØB ѽÞ0=ßùÕ¢òBÙ“È[MÈ[ÐÊK®ÒkÁà*ºËº $=õ°MÉð±á+ŠÃJòV ï8O žˆû¦d‹rà|¨dÛ»][u§7œø|!dÇ–:µæVsâK‚¨hH’Üÿâ1DXö¦ý`ÜY±i– §œäw¶Cì¦~1`S¤ŸŠ4!´€;Ëj’P<ìíî¿O½£:‰ï-É+™lˆf¹Yv“c¥ «@¨;þàõ>lÒ †·8v+r±k „m™š³_ŸèS¶&„ XϽXqfqLÀºoæ‹9¢0ËF£ù2+CŒ`Iˆ9aøbÏÙ9ŒÕì0®€€×Ë`îŠýA|Ã|q,ãÀ6´`Ñ%æB\ÌÖå$^X/ŽãöÄ)›šù‰‹meù{%JxÈçÚÍîqDÔÁüú&´dA°¬ç~hû°*l°Lùd–/5à.L!‚ðÒuJ,•ºL]÷s1m{ø‡ìÙ¸GÒÑuÊT†TÍø734 r‰Ãމ\lç\Φ–\e!âÑ ¹“ÒÑÊÒ•wÁzEPÔÑÝ`Us)èO cûÚÁŒf\Æ™®©°Ÿ<©D‹€—´ö2ç¹=kÎGCÆ=ŒŸ¯ZYEOlŠ(å:ņâpxä•÷+Ô v°ôãË¿ár4Ï “cR]—|­ŽíA=W ê S ˜YÊÿŸ0W¯r †gä ƒ¦\ûWŒŒqJȕ̫¡4gÌÈiª'?â²ÏÞ§œ­¤ S°³¥Ý°xáèÒw‹*UKj O˜¶DÛWj¿­z ÝE4åb϶…Àlµ±Cb&Cí}Z þ±:™-1ðéÜ0¢ê”5@JÎK;jÖô 8˜-‰ÝÚ_è}cî=É[ùæî…/~|ù` “=%W/N¤BŠŒmv0Ýo`oÌsêÿãƒMŽ3ô??ÒÇÿRˆbÓãÔë»b@0‚ác¯ iˆ)“9ÎýT\î—Ùô·Ü£ÎoYÕåšùýcÎ%Þ)),ºÆTæ$òRÁú bØ5›ÿü÷cb¢‹ Egý~0bt³c2?¸RÁü7¢gÇûᘭ?aîNc)Dî5î…i[aÂê…õÓtaï‚»OG(>Ý¿€[*ú…‹÷±¬¸ç±ÊöÅ%Ýoh¾/é Õ•éàŽ€‡"µ.vÚâÊäž\J 8D3“×r,KØzÞ§<ôöw‰¹Á#MçfìÒo˜g$w¸ Ù¦ sÈ©Ot;Tóym ¯šIrâlª%E@Žëè¾­½ˆ˜‰!'c™Jð¡kUB°Í ø˜õ ÛìªûôÅ7æf“…ß옺qóã¯oJ§¢«\$Ìܱ&† +/àŸ¤5=7ï3š÷ÐÑÊ áôÛÃ≈m›Ã4ÍÖÑÛJŽÖLÂÅÝc%½ˆ<9VÁŠJ$øDÍ&îÒ…2MrÐgF ÐË7üóYëÁ¼W¿d;‹B²hߘ¥›öÂÄwåjG ‡£ÈL{…‚…ïÅgí¡&“ݵYÞ0ùËY¼â}´)‚bíCpi† #©ûE!×hŸÄ³EE·Ä_7ÛvÊÎ…/»Hùû…)ÛæåDÖò¿cÜë×·q^l®2Þ#£A~æ;Â}¾‚˜ýé²ÍðveIàÆM°nÌÄŒ“n»“·”ŒlÛœ5!Áž•¸Jy}è³Ý§F>u£³¡:ÖhP¿àeëƒYší3Þàõúï Í=Î,¶ÂZŸI"[ŸUÔ$íA«ð:«‚>.2 '¶ª-|:˜a¾r4o:׬ø{'LbÄ_ âôë%é`Æy¾ crM`öÓüÌo*b佂¥<—{‰A«ú¦ÀÒ¿o­aÏÀEElò¢ò?ûpcÎN]#\;y}ãÙëk7\“<ÌrVñâ¦³Î›ß ÂÍŒ‡F/n=T¼ùÙD¾¹ýëyPÄN#îhëèñ©3æ¬ +¢a‹É=5íë@¬aüPXw3­b}Ó·ÜÖ4&Z_ï“Lˆ™ýº™¤Øjºh“¢‰D äwR¿(W4/ù-µÍ—;NÆmÚ/=ŸÇìÍ#ë[³I?ñ¦(‡±Ê­þÀí4?`Ü®ù4Oº–ä¹Ðf7fˆ¢¼Ý£[îÆö¯ñ°×RÖ^í£ž4KêÉÖ·¯!‚k±òñóp¥ÔvèT­t峡Yç°)*Ç;8¶áñ“§[}Ó°bö«ðÕmà´È:úÙWã®×Iä6èžÅ–ˆ’ç¿ÉýÄ:²tT]¦Ý›‘õî×øú`ºkŒo˜ž†³ü¦Üxèƒi™¢DM}pC¢˜5é‹ç¸TeÌ5žé53Ç«ŒÍ"®{Às„û¾ÿÞ­ƒùƒÁ#W¼:í¾™½®£Iè%bvT©íMÞo8>¼u`nL•¿9`mÌuu\L¬rô†É›Ÿžþsujï×sD¬9¹†ÖE/z;æœ-جyN‘BúD±ñ?!°D#j/TÙ á“zÈþ¶N½¸¿Î^%’ÛGü‹ø’âä¹-$o´y2Œ q·1ÓÅ„³ó‰¿·â F¸ÁÅ´:Î5ÞUçr¼¥Rt”Nurš/s*?S¸»]SèÎtj²rmE‚A¤'­î»¿ˆ;Ž,Uq!»hN‹ãÔÿÁÔ +r[O%•Ð*®;LÈØU<ý>¦øjËÏ=•!žÅרYîÀÖ¥ýþQI÷à…—œa²TR¼.¸XdæäòEެ“i¡®ß; Џý›8¯¾Ëv=^cERésÃ,2—3(õØÉþ eD.™ ‘H8Êñ£¨CuŠåtpon.xѼ}S¡ž¢ÂÙ>Üåõ¤!+Bĉ¦¤2³7ܺÏCT¡ 9ÿ =§éjýÓ{±{MtçŒôvŠ•<˜:ì; ÓWùpÂ<½Î|üõ¼Kà+­¹¨'Ÿàº¿ÄU<æîR‡5ŠÑ»ÃÍoÄΠtâÚ|Mìt^ÍŠpmæ±ýÂ…ï“FaåQcñNÃâ²ÌH:lUŒ㜖C+Š; Ë;iÒèÈÎËÚYFNPLþŒ0HjÔ«L™J`åì7Læ‡Å»êI1 3ÝO=µW¯<4ì^î’ÄöSk^Æ Ä-jÎ0œ‹®(¥¯(ù‡CîaŠZ,EítB¦ òTü#ä`Ðv¸MðÙã/P[Ѫ•ì DŒ*ié[ À%ì>L¥Õ^-‚,zŒÚÔ®9d»—ã@Yw`Se¼rç³ “øfIGnTò ½ì­FfŽ‚,g³±ªO”`0Õ#9ªyTszs3Å…˜oX͉ͅ×å\Í¹Š³hÍ~ õ¨Ò™™Š‹® ëi<ëCÂâ`XzÀÅ'äxëD/Ç(À.‘ƒHðM¸›W2C—îf)ö]%[gKÆTÛ¬2æ×7é¥ÀJbÚ¹õTY+0Ö–¶³ÀÊéUtsªxB¡¤ BŒ%ËZ|åfÝXéË¢•›W +Ãlל£Ã’i²Uo0쳂ªäºB ßÜëä¿R£$Ocâ/3©ºnÿ²P¾/—ŽkíÕ€'Ìâ&`7nRwn`Ϥ˜Ä)¨å݉£¹ûWŒÜ7ctkøå°©²ÓÕ6HCÞ¹rô;ÍçèT5[§¿¤LU$pvñ2G… Cô.’#k€SUjÊ÷ð² !0ö™¤áT1J¯qP#PµÆ¦ÝO‰B-î0Å"‰4®ájD[ œ[6VñæÉ?Pý"v˜)•+s=Ï€%ªUïM‰Ü¦S|k›Î´X®N´ä D]ަmn’¤u%ÉdJœžu ?#PUUئÂPiªÊÀùÎ=°êqUdâÝ€4F¾{_TŸK'$àí«VºHúfqñ:}Â6VWÎm7%Oi¹ã+"맺Ö)?’|HTRK¤éŠ êäöa'sCª6TïÓÔ­º"z'›´?ÓæíIÞëê窼[TXƒ8]CzV(ó80º·kò+bÀÖS“&xø”]7ìÆ0_ž×Ì^” sz·xkŸÆŽE„›Ôþ8@a&R{uUÂkú[jÜÝ¢9M#P¦¬ÉÅ£o¸úL÷2…»«g©È%ëw¸öÓÖ~·˜**«O”é"eæ_¨ÓFf±ŸBÜUŽr$…²Û3Õ½µNäË~|RÁÅt\°G÷˹\ûÔ´q®j.À¦ˆE•ˆíØR®Ts-tš…¯¿O“’Þª:9ÎŒö¸ªLÆÊe¤«èjš‹Œ<Ý9ÑÄgµd(UH™A§zZ’ÉyÁ‡©e¦\-òr¸hvÉSžŠ™Î#J* 5gªsÂ#ZÒì>Góø «+ß‘U†ã÷8ªTÐŽÞ­’§Õ3y+Qrrž•Ž#µ,ÆJ+†<馿5kìŠ/Ë:««Át!€ápÕtSTnNg÷¸»Ö)Þ§*œ4ԤĊ<»w!Øž±]5ní‘%Ìdý•´EK4•Hnö·ºÎœ3CñnCÆí«Ú V íúù»=O¤¨àêG]MVÓ;—¤‚¦]À·s—·3¥6|ÈÇoXBv÷ùiqü`äÖ©îXŒÐ®ã|cŽüâa ²fY®¥‰ åªéxIQIþ®+áu%~¹3]«vú#8µu«â…óFèìqt°V—J™ŠÈµžàxÕ6U–ìVŠŠ+º*¯Š“ð©â æ!ç|Ž?arΤð\èç­ß ?ìòsJ¶¸ô¬Ì+6¦!¡®M4"6šZ–­ŸŠ±R-ù8…r»T¤ã—Å®rJÅÕy›nÒϤ]‰™¯°\ï‘-@yfgt+â ÛÜßznÅ6oX·…ü'O ^ìÑý–îm½Å•ul1iäóQgùÚ ƒ×º=ðÒtźûè%JªëÚ%ݲpB‡¾Eº’N >a¡ž%;•=¦n…Ð4?;Š¬Ø |·èöžè…NÊ•mP@Ó¹RíDHŠ6†*‹¯rY³ÈÂËŠ×[Ð_¤¿Ï}c–ósÎŽ8æ‹ü³JžÓ²þXä­6År*4}¡;vSšÕRñ¸azŒ$xµ—1‚Ju-4Ý‹sÜéqª™àò•jñHê`YÅbƒÉ"ð£•Þ˜•]aBñsAYÍ\aÆõXØ‹×*¼¹>ÁJWH]QÝû¥Wç •¼–© ß&ß5¬cd‰ÊÖ·£ —hšÆ(Ž^k;•dOÞ2)?Ù‡œwŸM4’õ÷t¢¨W>Ñ5éª\¼M‹h[®\íäÎ&¢êE‘P© #lžø{“¤qLèîÌV”«ö]:_ö g—«©XË_¼c¯vÃt f¾ZœMSRP{Á\;îp!”³±p4 ÍAVÀR𩸠ùä®ì'†S˜= ذm]ÀNö'_`;CeyÖô#¬~ÖC­m½mñŽ«ÀwRÑÕ‚…•êºxV.a:¬éÀ÷«ÅvY¨ °«Ã·ö1_—Þªu6Îú¶¢ýu2Æ|Ákùéÿ…QԿǦeð²5àV® âKÏÓ är^<ì®ñ:ß_%€¤‚ªQÉm(ðô7ùd.Œd-†ãöZÉñ/‚åÑ\Ø‘ÔN@™åL7Uj¸ 9)ýÀthÒm/̯†ä©nŒb ³¼0ú9‹€”iKÎ’º`ÍbyžS^®…FÖ£J¶àíyÏé§6‰«¦O(ÍzQÑ„CoÌó)ë(ž‹³mÄÜ–š”\KšòÊ×ÖðÒW±òæ .Ké$“®²zןÖ›q®TIµ¢ÒÕìx’S(+€¾K²/2¥uƃ2-ÍéKÅZs¡aeQaéx­l§Ç= Ônò÷ži¢v¯/-êE‰«­'ÞË’‚73F³nÉr“y¢—,žØ®_u‚×ýÓ4ÊF\ÊécP¹b„¿ö‚N‰ðár‹çGê¹.I _¹ó™q?…'õAè†ÒÞ5Y]YÅøÇ^~0SÕ¶bLÕK¿‰r¥I>dSà‹lªçrØ+þ]º·éÖ\åÏÀópŒÒ*ÎæÑ¹Qeá¶ýA4…Û,%ÑòÉ"ÿÛB:SUv1¡º^v2 DaUÚW&>’Ee™äYÁ®ž¸u62oäœ2¸Eµ÷¶Þçoþ:°8®©°äÓÂ9¶z#‡]–.ܬ}3õR:S&½ë.Ï×S·b²\‹TørÝ äùâ fêê“Ä9ºT`šã*R‘™“ õD<âO MVšõ$˜ÑßRöµ¼EŒzŸ-ÒN±‚ê¸N#5}°0tC%žÃ6€üħRì¨çz©SdÖb^Pö‘:ÚŒ$ŠIE¡t t°Üô-“©\P¦uu‘– KðÜC|DÒÜï!.=@;`þ‚uœ¥{K¤.p'ùú "€31¹Gö/ n9³,ʧâ"s·¿Tq6÷ÃéâW_t6÷u å>ÄÙÓ‹äÂ?›ÇájÁÊLÑYºþ:ÑoåFtÜ úi¥.³#ëÀä"¡Šç+`±éZîÙuƪÜëÀgý’N;nfT›µý›”õ›Šø8¿Zr˜áª u#–´— Qq±- ¾T´·Ÿß8UTÆ—k8Æe¨@WA†|ÃtØz©¼[(»—˜–¡ Aº,lÏOhÖY39Æ iÔO‰Rôh××y1ëWJZB‡¨aªzÒ™7&<‚FÁSþ0}4×~0‡Œià^©,įØJx‰´ û†E·æh©«Åp´¾ÄŒy\3½îæ}é’Lµûͳçók2I× ¦Fqcð©h¯»Ë ‡xiëôË$íDgÞû1\×MË· ;¢È×O}fáEùOO‹z~-j(¼¶¡ßYù¸‰Ë‰|‚gy))ÎDÑ/Åàá¹á6Ï Áƒi|½ÿ*{ãdäÇ:ü'Óé°UA|(Çø¹Ô(‹Âò^ZøÞM?Š–ŽÅ¦Pœ˜û?i$Oý¢»ªX‹ ú-ŒÆ7’Sma0*§¸å$¥ÉœãºOþ­[ÓcÙ?dªÿsFú%%I~å&»µRšõKŠúÉ*å§äú'¥¹‹Ï§‚@?ÉÔ*CÛIWD™ªðžÈ;°zÿ÷ÿ<­…endstream endobj 6 0 obj 11986 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:09:36+10:00 2013-08-12T12:09:36+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/absolute_central.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000012291 00000 n 0000013974 00000 n 0000012232 00000 n 0000012092 00000 n 0000000015 00000 n 0000012071 00000 n 0000012355 00000 n 0000012396 00000 n 0000012425 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<7580AAD9871AA51833A304FC0A633CA6><7580AAD9871AA51833A304FC0A633CA6>] >> startxref 14221 %%EOF opengv/doc/addons/images/noncentral.pdf0000664016516101651610000001735313344612246017140 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœ­›»’$9rEõþŠ”)ñ~|e.Å5JM›¡F )ìïóžë™Qm”ÒZ¨v/8ܯ¿PÿýHG~$þ?þõã_ÿ6ÿøßeµÇ?ø×¿ýÛ1r;ÚzäYÛ‘æã¯}µvÔü½«<¾~üÇ9úþñ£ÏUŽ^}죖æÑiúß,Ýš†¿Íï»hÒ|ŒV6º8ü˧VúS»#%†å™÷±¶–Zej©g}û «®zô“WcTËÇØ<šÖ× ÷i²§8k½ÆÖ?´Ò÷­§~Ì¢¥žœ½Ñ²·~ñvÕíÕŨ^öÑú£Ô®KCVïóƘùÈë6F{ÿÔRl>¿tH7×nòï«Ïc³Ò¹õÌ]Iô?ùךòâmÈŽG(PÍhëK5Óö(Á£î¿ <.ªø>OÖµØöÐø†÷þ©¥¾9휫ãZYø’ q“Ä:›×¢É4fãS˺À8ç,!µ;'Í‚å+<*‡Cüœª=é}ŒºÔãÎé‹`śӘ„^ûñ:бó7ÎdÃr{ÄfuðË¡@Ù’¤iš×3qä6jHGqiú&)MI‘I~žï¥áøMtC?‘.èG®{0¢y)ÑþY’¬v>I&dG'çëÆQ´è€£ &üÿ³@±‹£ÏT,GôÄGŠÖÕç¾½±D´!Žü 'é5Hfwè…~ô\Ê5Cî_¡P'²J+0Äh½(¹ö‘xîI,igY¢1É{/s^c21Éþ6ë»ä¹Jø†Vfœ·Ñ3Ñå“óuãHœÏTr0ÅD-;ã>æ7œÜÉí4KGÕY~ËáÂ8}“‘L]mCs¦¿õÜá;çÚῆó†ã|ްÐ3bî±½K¤óetJ~í Íœßüu~ÕM"‚Z³ÿ[Tÿ¡Ï ×¾Iá°ìÑùÕÈÅ §CÁðé“°V-KË7ãéV`Ëd/$ oÓf·™”é<õŒE>²Ð ÙÈn¹S§uB§û˜aqjæ·äEžW—ê_îåÑ‚ý%Ej-мÍ÷ACëG®ø™•| mÚ®5®F‘Gq© 5³ÔYf€ÇbÙItNtjžãra¿Î](SbH>Ýú‡VúÓ©wwQ¡Õi×äà2ñû‹óuãHK$z:¾âHEáóø6äQWÔcô¥Išø;Nß¡ÑJDñJ«#])嵿wε?%ԊΖœ\RæQAš¼û² „ŒÃ¡¦%$ƒCAïfÙf1C¾Õþó9„‹ÇïÝ& x2NLI1fâÎÝ|EÀ;Ý]Ï*›ä-jB$‚”çï'ò!p(õ”› e{Q<:–3Êié\²ûtÐ=»âŸF< ôfÛã/Óf£¢œS‰aìǦþ‘•þŒºÈ5º|´’Y–ªòYø×¦0Dip-•T´7¾°E;Ã:9Bq2ß'#÷ >âlA±ä,„´õIk¡méOÎ×s]S×HÁâÎÙ ½½8¢7¾è _ß-(Ô¹q6&LtÒ4vžÐ`Õû­œš£ó3‚ëé]až!e–Hü•ð×箆ÂqÁH®a;³ââ÷·1JÖ‘Ù}Ö7±£D¯¢"™s3ìöH º,á÷v"ù½ªXI†~"¤a°§Â!0Á.ߦë?0«§×br £í—H¨f¡¾ ºÖP„XË£hãQ¹,ä¦QŽƒ¿~3O³ R®¥l”9ÌáCK›¯`‘6¿¨2h-Ê­›8O‚Y!ü¹¥YÒ ªýS/s@Úû¤)û³æ”|3äO¬ó»š¨r-ÍÔY¹#›Aö;§h[L"Ö’æ9Ê&V·”¹¢–ïóï6’þÒÞ§O-y…!{h€ÙÅ"RvÁ›tŠè–S*ù‡dDÉΨóº ÷u(uVj”’™mô}äTèƒêW«æCKq¢ú•ÈVQ}ªÒ”„¬(3’Nò»J.ˆü …ã¢d;âmN¡~NJƒù–Ó–?±Lì™.U0•(¸ˆC¡Ži¿bÐÄü¸7 y )¸¨‘®¼Mky;ÒÅfmûC+Yy¤aC*G'°ÈC,ýg7\ãÔ¨JYV9{£J= u»¡ùÿ³†Ôlh—¶±¶W„g£jOÛÁXG_¿~³ê(TNÅÐ)ú¸bƬt*Yr»jÉð—ÖˆÅ6}Ši*Ÿéz@žõ,ƒŒ–§› ¬ïÓÄ™Qˆ•+g1èC+[wX¥ciɨ.$‡œ†…³v›ALi¶K޾9åá²6À# çë7óÄIŸà4O,ó­$ý,8KçÃ.ß–JôÉ(D'¿–„Œ‚’Rµl~ŸG´ ÓNJ\Þ+¨x¥$«‘ÃþºeÔÝzd-‘6B‘º y‘8íøÀÉ Ôõðì¶½§–çô;y$½ijŠËÙ•¶æüÄIù޽÷þ¤™°·sâkDM‘ůD¦Sª;Ðýpñ¤ê’Çð÷üñZx3vk|¢–âj&à­›©â@ESr,ýÄøæŒoâñ©‹Ë«&÷}é l§Ã=¤\U¢ipÑ–ØÆœ^#šCÊ?Ø\ YžÛ û’q±¯òÁè ছ÷Ýœ?iÝÊô„‹A%ÛKºá¬[w!X[píLZáÒ•õd9KR9ÜLeiT¯µ€p“åIspKó5@7ŸX@3õÊ2‰ß×ëvä¡w ]õdäu©Ð»Ñäç#fœ]Ïâþ‰ÙSr{Mt²~lÝïŽ .ÁUš¾•&¼´› no·,½ID}Òç)ú¼hN½&%»“nÔ?çŒ'‡ e„skÅe,2¿†“n×òÔ¯ ¿ž§½”âFŸm»G,Øöê2š—Ň„ŸNQFɉ`¡.•h“®Ãí/å·mGS®!ãí6…tŽ$xµ–·MùxiiðC)K¹"]nÁÆ2‡à‚€·­á‚¦h«p[ÍE¹]ýJÃ3NN¶-²Ôc%ߨ è×5ú•mǦk5¢ŠÊ.²ñÁ-!™N¡ÝêMÈ[ÌsS9¬(X]Íêš‹J®lóÀïD»¡¹Úå5¾4¾:ã«n[,«¢÷y~uÚ¼/ L\¯‰`‚d8åäöü}åtží~ñ¨Úsrçd^¢–ÓY+NÕ¹Œ‘y£eUú–*å¸Î‹CÏk(X  Q—Ý Î»Ù°›ÛD:R?5‘…èu4¹‹fÆ)ÊçŠæVÑM%`ôd¬}]ŵšձˆèÉö¥¶›(äF'VòŒ“£m*8=~ŠvÇcPÖó®¢ÙÈŒd»k¡Gš÷Yó¶ÕÓH:9ƒ”‡H?KF õ—Û‘Œ”q7О¡«*÷AGf‹.J©Ÿlžå¤Éqã$"¬§ýp£üSx3ʯXÿâ Jí^€ˆN—¥åiö¸vbNŽa_Ðþ¦[c ð ˆwNš2áo#¤§ÑLs‰é\Æÿ <NÕ{>²[4ÅÙ.ùºd‰>‚ó­à……’[çYN™xk žÍò"'l0k#b÷xÂö3Úy?9¢+?c+tì /g€pwX¨8ã|„á.•pJ7:…Þ<Ô6¼ ЕtËuŒóà?ßDíŠèí.ž© Ä»Ä3)Y×—xfvKî&?ýÍ/ñL®é%)å²ôžÒ™Õ‘ýS:T0K:ÛG¼o8ñ±°ÍÓ+?7!çoMI0çÛˆµÎŠZÙã´Ÿ~*Å8"\R†ºæw(Ošh.&œ õ8uu9TËo©ÙpGÙŠŸyd×C • 4¨h=iä¶¢>ú1]3PÑ7ÉÃ%'Ñý¬UlâSj«dKR0#5»‘ËÕ&<9.1hÚ™…rGÝIµö“f“s¾±Ÿ*ù÷œ½åæ«>9Æ|—3§_yØ—ÑÐ=N’œ­˜ªóüszg.3Ù× ¼WqAFœml¨ /žÃ3ñཇ3žø;(>Å©Q\~a'º ðÒž u¨©OOqU¶æç)¶Ã5ùÂ䢬3™qùWû&©–/,ž JD¹´xIœ{Ò⸦SZq‹(cC`IqªÖèŽ[gª{áL¨ÑlÆÁÆŸ”åü…)¨Ycu]¦ÃY²Êb0p óå ã´ÇM~[ÑÈ® ª;zË!¦ÿ¡t;î'9ÒYz¿qxfÜœí8XZ¾ˆ1Â+䥫qá{ª'¸PvÁÖ¯Àö3š€D•}Îøã­'D1´ÓÛ9q•íŽ$hÊ<îŠKI…¿ ‘ìÁÃg°g1H.ݰ—´ãOY9d4®Ðj¹ÿ ¿‘]â÷Ã8¿ ¯¡ÀñJ²ðÔ"ô—†¯ÝF<†Cl숖ïç^t>âæ/,bcÍN‡›ÿF Œ×аmûÑ/¢r=8|[d”Ïó Ô=iŸ¹ÅžÎ@ÖŠ/Xµ„§›b!çt†kžÐGH!…Ù’ylß<ãbÚUvd­G+øºÙõþ_nG÷ï?þÝMÜendstream endobj 6 0 obj 5340 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:09:49+10:00 2013-08-12T12:09:49+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/noncentral.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000005644 00000 n 0000007321 00000 n 0000005585 00000 n 0000005445 00000 n 0000000015 00000 n 0000005425 00000 n 0000005708 00000 n 0000005749 00000 n 0000005778 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<9C470D87837B47FB3A3C1A0300957906><9C470D87837B47FB3A3C1A0300957906>] >> startxref 7562 %%EOF opengv/doc/addons/images/triangulation_noncentral.dia0000664016516101651610000000502213344612246022052 0ustar dimadima‹í]MsÛ8½çW¨”Ã\@ãs4Nª²µsšÚ­šÉž]´ËÜ¡(EÛñö·ʱ-ƒ–M,É U9‰ ú=4Íæ/_¾/ŠÑ©Öù²<„Ç#SN—³¼œŸÿóí×Ojüåó‡_fyö³ý™WÙbd£\»wg㫺^ý|zz{{‹Š»uV/+Tä×hmNÿ—EvjŽ?w0ËêÌ}¶ù4«ë*¿¸®Í¨Ìæl|‘MÿœWËër6nZmÚM—ŲÝdÅÙøã¥O7Ýœ>éç…¾WÙÜ\T&û³½kl_Zwézeªín«å:·Mê»Õ³&-ý¸?µÙ´ZÛFåüóÇßL]›êc3¬Í‡ý…Û T/²jž—ϱìõ)š‹Aí^‚(˜J¸¿.o‡»®®._Ÿ¯–U]eyýòb¹,LV6¨uumºã¬§YaMì¥i‘î½_æu½Ü1þˬX¿fÍÇ?÷VöΫ|ö2yŸ´héå6ŸÕWçß#]®¦÷»H½ßäëü¢0¡ÑçeÝ[÷wýt¿ýíxøõ=­¡é­u‰˜)à û1¿Îgf½ÃÌž¶iééjÓìt×Ußn÷Ú Ó|´µ`{ˆ"»3Õ¦û¯Kõhóog”MëüæþÝ£k²¼ø¯™Ö›ÉþQgå,«f£O£ßòÒþÖGĺ!ùìlüoüôjmÏÏöf…ðÙåZ-ØSˆI,OCT3º}%žëHÌÅÅ6Je'’•óÂlÂJ‹†hÁ'™!8ݧ˲<7åÌϨÓ<M"ÜSvRy½˜®¶Gâð[:µ«Œ9_×w…ÙîÙX¼Í¸wtÝ|ØXw‹#ûZ•(µß„]ð#š›…¡\óŽ!RO˜F ¸ö°hds O2`k´íì(%Oö°7Úƒ½ ÊOˆ@”F68Εv@Äþ=‚8•VßÂD³øšåó†vXÌ5”HÓC²8;É󬪖·íGéž]Ÿ¦œ×WÏ¿È{ÿw•¤ï…îƒÐm Ú ê9xÖH¦'ԱŲˆbÄ@¦ÅkHãÛ)p£ڕˉ6‡OvT«ÅÄ1wk %ŒxXÍh©!´£LKÍ»å ïcG@õÎ2$ö¦€©bW)`€0Ýl äÄ Ï3@jÝ37LAAÚ¾àiø'xüàN 9€œbïGÊob®fDªfW€ò “H­N(A˜i;6˜b •÷­¨ÓZöné"û Ëlb-–# ؇¶¸Äà Å`Ën²Ø!¹ñA¢Ê{¥Šêƒ*2þÒH .ð/ …‰EÕŒS+1€,òk XF»v ©Ä˜÷ÊÝÇaá±”ŒÊ‰#òÄÊ8þ°Ž€ò‡uLÊë‚ó zev|vœ(@Ú)%vîdç?‹"_­ƒg›û§ „f'ÂE¯Iìãtâ‘@[¤‰}Ïwï•îŒl ³°F[•Ïóðúž¤‡ÚùÕCW•óÝ_™|~U¿Ø¿~ôRÀ:®¾ËjfªÝÓ!¸y¦1!¢ëµËKûí—k˜¬Òƒ7¨ÁÛ/t¿0¯Ý>)Á¤E¢Œ3ÏÉíöIºL5€GžggÂQZ"Ügû-no´Žoæ{ýÈ:Ƚuì}ˆi¡¤‹ˆr!#Ç=BZi°Âx\Í;~µ»(;òó¶Ú´¥›ú„æ'í¶òŸ/[RŸ_ÈlK>]–uÉ}>ºÌyqw6þ–/Ìzô/s;ú}¹ÈÊñȧŒœ•Õ…¦ßâÓ×e1{léoÎ3)fSKKbpÁ}­™Üó©I¾Å,» mËù«üÅ.@Y‘ÏË… ½¾ãkQ‚)“ocÈR» èô±?Ó.Œm-Ks »GÂvベJÌ5ÕG S?%¡R¨Z-3)Õ1*ÕÞi* ¶za7rTF޾:†÷‘WN(#]sc†Ô¨ÕÙ—$RƒŠTØ(£IÔöþ8IT‰újþÊMÕØ;7ˆYéð'( ‰¨ùt )±É‹f*†¸KKÕHIÑ5*dþ:ßO0°×ÐH¸Rëò½Š”O¼ÓO“ùHæ,;»`á¹3‹u»ÍágÃþ_ÿñuGð‡¡‡¿"…îñ‡öÎrÏ—% åQÓv78ÒQx1*=¬èèÒ#ú=ùCƒF—ÂFÕz,–Éêñ€Dö%ÝäˆDã¦H Ũ¿!‡ évmJk'YÖ’ñ3¤s ¢ÈM^ ãGwèOŒéì”$Ï¡_ÏAõà9ˆÆb™”‘]Ѥˆiç9ÐæÆ5çÀ¾ãP'Ça`Ç!h“Ñ<‡mEKžCµwÚ µ«%×þî@ DÅtî‘8" aâîx’B¸uš ‡/T7«a•ê×ʘ?L•_>hÔ½Dýcy]å¦zúÔj)Ô{„EûÈšôqH…‹~¹²~“/@$À£êc¾Ü¬~JÚ4À!T‹-&i:FiÚ;-Õî´|ŽGÝÚykq‚O@!ª›Ã}ÇäÓÿCY"®ê†àœK޵pYÄÑ·t;Làc”$Úƒ$±æÀ˜AdUbMŒ¼,a_ËL…³4Mš4ˆ&… 1ÉÒ1Êô!K~k%#k’/, Hã*mjb‘\¥$K톘"ßǨI¬Mrj!cûIîXNŸÒ£Á9ŽÍ[¤aiÛ “ aí£Ô¡• áBs7cJÜ?@ˆvGq’RæSk8¢°npžáªˆ| FF]6O†)¾L%<!›‡îL]Ê%øåœ óÎH)¥™ã'å‘'Gp çMÊéô̼Í2£yÛ–<‰=‰^ M2é3`™d‘«MJៜCDslÎí?|M;¿XË4÷83A}Ñ0Γ‘üˆî~„ê!£…jWhœ#ˆ\¬A»¿äÒ•N’‚ßov®f4¨‘JA à6ÍäH£#¡{yú‚ö&µŒ»åê,Ï"a‘¥½rÅ/)Ú:Ë §Í°«ù´<²z¼$­ò¯~Dîƒ:ÀycTXÅ¥W®Š5A(uÜa˜ysæ0ÄÃåÂó ’GpÁÜ@*–Èó^ÉÓËs@¥EŽ|K+•¢A"@Ý3æ&~áÁªkÉ×7‘'8Ï`A¦µj¨Ö Oäé•<´—Jð”4Ò1[i”hˆ«â¥í¾’øpR‚ Q >4Ïà#GÖ¾h¼ÔŒ'ò¼WòôR¦“qÿ0*£ÞéÈãï´+Múy®°!¨œe:D1æ†I@ÉD÷JÖu6ª¡:n…[÷ém²©p«ǬáŽàp'8ÍàH(s;3@ã´á9|î4ï‹ìÎTŸ?4oìϼÊŸ?ü î̱ð‹opengv/doc/addons/images/triangulation_noncentral.pdf0000664016516101651610000002670213344612246022076 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝœ¹¶$Kr]õúŠ”!$|¾€2Ñ"¥‡Õh¡Z )à÷yö1ˆ¼· ZI|O¸e–>»Ífÿû•Þù•øÿüýëŸ?þõßæë?ÿïõñ»¼þ—Ðÿñ£¬wmãõ_?ÜúõoÿãÇhu¾W}åÛ{ö×?ô¹Ò;åWµ½kyýüñ·­ÕwÉûUZ©A­ÆØõÝÕªíýË­þýÌÒ5Íί\Ç|7†Ìm±´Ý²ðÍmcÿç?ä>ç;××ÚëÝÓrë¼Þ«“µô®æ¿ôÏm²­WN%¿Óæïÿò§Fú‡V×kï=>¶ÐëâçÚâ@Ëꯢ†3U5hƒÉë«jeWµúÒe$­dÄÏ:áXñÅ«ýõ¼sæ KÒÀç sÛ .IÖâtJ÷¦«ïêW}ßûi-û½—03Eú ÅÚóEˆ+iêÀÍÉ Kà ±s¢ßÏ»5T³õ›ÆÚ­é¢Üxé,ÕzÕòöMïW+o{Á±•?1Î?nzÖ>úØjŠ Òx'³ŠÎâ]…éì{}%ÿ‘wâäĦ:ôô§†òâ+õÅ÷¼ò{‰=ƨ:š`ßœ»¥ÞlãíÃêEãz Siõk¿®å¼‹¨¼Kž˜áá?4ÔfT.P›¤²¤“O$÷òžãU3»-_¹adû«–Ô™X­KYKj¤Uß³ù¦¿÷ISK(ÖÔ3bóPÑéŸ$Þ×Hȧ–V{'˜ìÁ0Ô~õ%%”‹Ä‡À4™á€éRçz·ç÷ÙE¯Ýo8& ÃÁp9t8ýsK1ß™àÀêp­ànqVxø¶…¿~üýƒãÿÜ_ðR¯-5’Ž,…íš‘yuK†ÏüM&‹¨ßÂàÇzéý2oÌÏ ‚Çòõîµ'üó)RÉ£|Áh®[T\àÄW½$úÖ"‰·9Qa ¬e6 ¸Ü« HÛ;e”*Ý72žÖâ]É¿ZS Ù;«,<ÝQËê/š‡ké¡—ù#ŒVVƒÑÛ5û¨$”ú{<°zˆK8̧E.È Ãˆ8È3Ó^{ª+0ƒÅWc˜5 ÑÊ<+XÃ=t9ˆÆ4ínxÌp5¯h_šC ÞTÃWD‘ábXûw]C‹)ÒòÝ—7t®q7¦X†û¨ejS°„‘Q…XÔÆ’[è2½sõÝÀ Æ<Ú¢Ö,Ì~ÏGÅÒp²‚Ú¸aŸmcèõáªog!=¥î€û“ ³V,*¹EõiIêžÏ}B>¤ƒ†*¬izhÁ“_Drý >=NbFÝkh6{Çm”fZ}àbmáÉ{p>ºí1~ƒ¹9êîõS¶ÈÛj^½2ô]¶mnŒ¶SFp¦}û-æîuøðcäoÝbò¼[Œ è¸qì9Ç”©»öØ¡ nCZp°WÔËŠû4AH¶¸¿nFEY.nèMÁ Ñ+¸"e}=ˆJ:œ“ý±‹2'Š÷‡õˆ;Œ¤yËq˜1éo0Cݾ#º¨»ô¸€ØLG«æ/mÆf›ä»/ýw˜»×ņÏÈ_ùÝ"@8SÌ5°dãosëÁ`Ñ‹’ñ´¦èi˜Fô“|b¾Žóó¶»°+S ›¦Iöˆ4ež$ï0¦p-‚ͱ‚;÷,X¾%àD-È,JÅ*Œ=ÙŽ¦ƒmlI÷Ù^`¶²¦Gµ¶¦!6z’ÖÌŒ )4è(`J MS€äLçjò©Óbä˜s1¡H´ŒÔVn mâ·,V˜^½yWâiq§­ ï’æ"¿Ìbä’Š™dÉψ +7Xeåâö!*–ÒS÷í ðÌ;ݵÒÁïpÜŽ l‚µªÛ[ôÀÓ®›´CjIÃvca·Ý=ä@4Zh`ùF¸—­È|Z´FM¦çhpÀhA:¢ž"#Øa&Ý:¿öa&„ÀÓÂaƒ€eéz*ºO°ÓW|–¬Ímzd»íÍ& 7 *Za_W,L̺‚—Í`FJÊ ,!Œ Ù,¡ /ZHf¦û”tMýô`üŠÖàßï}ú†¡ "Ú;T* Tôœ…ùŠÆÿ×°ÔnLž5ì2TAþ6y¥ïýÑÐn„eÂüs:µ]MŠÏ¸7¦lØW'Hxø\?Òm5{j¤gýŠùÂÊ?ƒ4piªfJŽÀݘmÃXp„i-aâ÷´¬ÈDüÖåĒܬhÑÄ›`bÑr‘bzD7gЊäD¡E(ÛN¨Ê=ºm9q«õ½àEOzŒÓb„_³[`ÄqXìçxè!Š]ë£aVÙð²Ìêû°T»aŒnÃÆR­Ç¢Æ|n¿uK¢ÛÇÏÓ§‰–…‚–—Û‰Ê!礨°"¼Ì~ƒÞWe?OÉ QJˆ%Ö  OÔTÂòàüfsÿsW´¾¾ß&þso¢-¡Ê0hÔ\±np¤söÿï0Ñéç÷Qô³‰¤×ç¿"ÖúÖeÓ1КåIŠaïx”íÆtŒŒ¾B Tûh·²•Ø Y…ÄÖBx—}„ÄIØfªåbÈõÞŽ!±3-S¾†ÀbrÑ!†Ø=SÈÉ@’ãÞ”ý‹gBÓ<˜aAzPe0~L\wtðð‹gˆ%âŽöMÔ¼²¹¶Y‹Iä>†J¬x=UÑí±‹s”òã°EÕwt_Æé±,aŸÛLôŒ Ýåò9džEa\«À ΫÄö*ï}`ï¢r®â–öœþk-ŸG5Ô·•û,qx}›ç¨øºŒs®ëàºÎkŠç¯E\$q-ò¢˜kM]½¨î:ˆ›*ÏQ}Ðí9Ì›²Ïaß”ÿ•7Ü#tJ•Ù°‚[´ž~#~þ0,Ä›t×Ì´åÔóÆH¸LĬD#v ¾ǃàÖ-zµ˜ó¼ËçCaq~©rn‚¯Kža”a=´8¿ìóCˆfîMw¤pñ%#¥×u~ùˆYÙ(HÀëÎ0üL¬slŸ—*ÙyèÆ2¶ë.}þÙ>p#Rµöu§˜½:Àê;…A:ûŒ+Eµ÷.çJ[Ì éÍ¢û–ý!#6ñWì—#¦q± R]gba†õ‰£c~‹ Ð é•Ü¿cBÍènÐÁyɈæ3 ’¸ï¬O¨\¾M'„Òh@\ c€>‡æ Sc{)äGÂB–‰>Ȳg›Öü…pì˘Îo^-†¶†¢·L‚Ĥ 1ð·àPËáûœ’„Y²eÔ‹ã^7Ü6Æ.Äš!Ða5ܬ±F8#²¤ òX·ýÑÉ0Ó¹ïQ°­bóA 91fŒ)»¸yÙ)xÖ!0$ŠU­6õnN@ÑvštdAÁæTIº5.Ƴ‹’lüüE D¿%¡qß²ç!%Ÿ)×±ñ*‰Y‘j&yCŽôœ6‚ˆ¦ô-œÌ þv†“?¸̯Åál§%“®Yœ° Ûý>€1ót²»EäJdÿ¡‰¥W½I” oÄ{=s»ƒiR( ¾èEÒ?1aÐýüQváf~GÜ}ÊÞÍ~Ä=î…!+Ieõrö~9áöƒ"µ§]s²ëÿ‰©(m8K>I7<±J µøb¤? êŸÐŠÛ '-”#‹Ád®Ôƒø*Þ„á»Ið½T“ÿ”]_3Ãׄ;¬Ë…‘9þš¨<‡^e’¨!¹å(a°òi¶à²„ç,÷ÜÛÄdGsÒ$7û‚§#jÕaº}µ… “®Öî ¨&ó¤F·Àâ׆+¤C£™e“zOj£•0oÇÀV#IR#Ƨ%­Ø$4åC3Ð>iæÂ\$¢iq~¾Ù‡þB´ÁR¯>½:Qå7F„Râ Ÿ„«’NpžÍq£9â9”H· ,œÜÄ…pQ÷ ðmÐ ç&ÞÌþu%Pײ4žèÏ‘”å¯O0”í’†ØL@ò¤GJØiŸýxÁÝû¼0;Ÿ°àÂdnùÄdÇ*/L%Æ‘ºo¶MîM”JR ž†0I§Át^½âQ.DClÃj¾,å}LÎ=HB²úг-Í¢†’+9εC‡+LX¼ôÆdUËÙµ¸kÁüú~uNVJQÏ!IÆYÅ x­ó• Eò•Ý]³#ßû·ßv&þætP£)1{œ-¤uiÒ5¡©¿Ö¡BòQB½×UógF²œÍÔ#½rÙVHí²uat:Óé-’q¼Ë@’€‹ïÃv0Ë9½,ŠÓe|]ç.›ÃÝ‚gØŸÂè!Èœq½Õ£Œ7ìdMµ…›ñ9rt¨öƒõ§XVåÈ«ºFf|€åKt ¥7¨W¶Mùï˜N¸:½NOÓ-äŒݧA¨ÜD’…Eýs÷"°5òï0ÏìW¯_1µ¹6‡Î7LÛn{‚mâfÜ·ÁÙ<‘‰Hr²%;ö&8ã±Ö¹`zT'¢žuÄI—r´‚µ†mvW¢tØê±„'Ä”ðZ\^9aR‹,XuôñPÈd’îmÆÌž4òÈÒÄö2$ô2T$™ílª‘ ­Žkš*C¦ìcce;¨ãìxŒYÆ(ÞA×§‡DÌcÊ÷N´Þhq8á «üõ[Gó ©DÉv¹þùÙ6¡3‰üA‰\xµPn©„ ôïq-Ù›EÌen›]®p‰|ô .§ÔG³Ìø…ÎKè&Ãý$áÉTRVCÐFããGnƒ.I¤è»à‚ÿ¢¸ËŠÿn±»zƱ™YQÿ®#Qô^“é¬XÓAt8>A§»èpa’Ïœ–e¹Ôå †Ï«%mâj¢î…°ŠSmqsÙ‡Œî!Œ† 8E•VÅÿ€Rtô$bÊj6ÍÿúANÜP{XØOŽ êKæ• îâþÿúÁ1/Ö@…KÂþ€«³>$/LHqâÓ¿EZúì+hÝ´âTÌqζà\šãðGpßd&™©‡ãïr3°$-qµ%‹Zr^§áßhO’Òs–Ú‘À 3ÒÓHÏLv_|À†Ëâ+0Øj3Ÿ”„H—¦v~wósj Q‹Õy¼'ÓBX©Î¯­CЋË'¹…íœ[d–;J¸— q0[Â%èÓô5òµÓjÍ IvŒ·ÏíÛ¨"¿T©OƒæµLl‡ÞûÍ“™ƒ—L’åýÁ¬ç°\Cø½Y;­«¢´YÞ5¬”…F@þÑR¼ç\MY"À;/®)ë&·G\Â;+£E¶I›@á¸æi6VSëoDõ¤³ºUÀŒHïOçÃèqa¨ýí³w ­êJ"hÉ—>\jÂ>D¯äXoS²Óc%;”DÌôˆ«5d(ðaïØsÒÂý"Q=í_äR¢äÁ^cFRR` @A6u~€Q¬7F'C¹EO–Í"Uô+‚׊ëÀ,éÆÓ”òão0à$L¯ÉuoÙ'f³úà M°(W98fQúëmÙ¢í–$¶—í2)’0ž l@Jž *¬ÄB°¥Qå R:pŒÐœ6¢Do 33FØgmFÕZAíuŸ¥“Ü…Ø]b„H9Ûàc Lìv4l,‚Tð°g–9Ÿ×çá¤1 jàu}.áÂD„LÙ$Ǹ]–b?¾8!Éh¥Å B‡`xÔX!bcÃaUBR”Ó‚ùåt·3áØÁ¤†=FµQr‚ ¶-’‘û€WDðL¶X`XÛOÙÙúB:0ž½ue³"‡u¦ê Œ\¢ë»pƒÅ ƒc>#+«lƒ\ÑiU±€„ô#Xpm3¬1Ú‡ÉcÑ#Ém3L*2“E} Ó×>yM•!*ùl›Ø& q*é)Œ@™Aµô£4È(¬¢ª„@Å"§H¬G˜¾ó˜YcŬ…ŠŸêÃCds ­<`;u¢ÄÙ"Ãê^ÁÁÚ'°óÝp0 ¸M$2½dxªõ¨U,(™»zg0¨*0•Ü<öa#´¯àgÖØ/Q7-êð×¥\½4‚×q ²yä‘]ñI‡µüj%#þ AÝ×K|r¼¾_7o$œX©d4qs5ÞX~/Á.•ب‘æp"½ ž–GØkXÒ¯C¤FšØ%/j±5xyz:L«¦ÐA¦]#r"ñA"^Ä·ÉÆDå©z‰ ‚<ˆÉF†`ÝÛ`M”kîÆ‚±Œ`kÜIÀ/}†•7=ŠÇMr³”ò¹Ë›ŠârŒÆ©1ÇÁPšKDˆt†ÛßÌXÄ¢Ø-ÍX•Eç¢ÌÉéï5<ŽváÚ[ŠÿŠ‹F‚eb¸še³7ÉÓ`ιx¥EŒÍAÆ‘’‹ îlª öv9Á,0/'‘.XÆó^XŸ-"ʆ¥Uß0np;=ƒ0(naÓ®ˆ:ö=Í6‹ü”ÏV¼xCÀKpe•‹Š;±O§^\ ·h:Ò÷°ÒÙTazÚ"·S’£‹}Ãú¯7ÒcÇÀ×E²d»är“”Èè»:5qÁ4¯ÎA=-TG ¼9‹·«XÒÁ4‡)2İÁÛšã|b‚ðæ¡SxUG¥[ SJѼ#ÇC¡rƒÎÀe5PèŠN=’œJ>5‡øŠoõ¾æI5¦ˆúP0¤©Ìí7tÎúá’Nä¿–ûS·Í5‰|ÇYР~®9Ý5(4ÑÝP‰2("°8K˜#YDˆÞac°O™úH®UÞõ§È–"]K¦sõ¯x<"²[T…8²xZvõú뻳P#Š5–ï é7VûºÝx7r¬™š‘·Ë²¸âó£è¾ë#Awû”1„\úül1/™U?ph8zà€"¶•ûÏCw»IþfÆ€PkHÆÝoŸ ºdãcPQžM6 ³íÛÏE§\ŸË´;ñ! Q=Ýthá‹Æö¯SX[ÒE¬5c§ê´Âbþ?à’¬šÖS‚,²¨ÐãrGd;hOI1Ò¡Ùéa“”ÀkºÈYtDÉ;©ìPuÀDdˆÔ$¤uÿŒ][ÉÒH@ uWΡL¬ÕÖ#¿àvtäp·“4FØéœ®3½0:TïksE¾#%ÏÙ¯üGJÑã`êtègè(×/˜Æ´ÀR»øhLJgjh14òãÈÿíg``Ì.Ô¢ÿˆ0£)Á`Àí@•5ŒkþØ &©àÈEôâÜž5èi˜FÍÔŽ g•¶•–ƒÔ£‡l%ÆÈhÖ˜‚*/2Ç`ü˜'ù‘™ ãWÊÕK¯¦H{a° ΜeVÌÅ¥‚¼Îùtè¤'(V£°Ñr‚ûvàG‘èÓ2Z Õ]]?I.VÖ îé&˜29µ ÁÖ=ÜRäªvèahGr+ûU¯ÀApŠm9&€t$tÈ]eF¤Èáæ,§ õA [¦¢Q„¾àm:ˆEZ¹ûØô˜~2ä%•<gj-—Àú.Ò`;qU?^ÞNe\d‰ SÚ³\²d:X|Á–%ÒÆ|t!÷À8µí'…nëÝò ¤©ðÌiZlXÔ=² dîi7}ÁΉ”¸47ÙJ¼ÆM¢8”‚ÎÊnñr(ÿð– \•WÙæá¤ön9 òº@P´’Îåˆ\U1‰Z¤;eçöy“ýhÑKŒ™¢àŒüݪ¶¦Fª®nfgÝïÝå=a Y ñolŸÐ€Ü$N›FJ*–9´C`y`¡å×¥á¨äÓ¼ vÝ€ˆe™ÿ¬¡L|ë$†NÆóþ·Uê¾F\<:±¦(Ê9ÚK<§\Êpl³/`>‘ˆÓÇéŽÌ/Â1©…”Lû#vQ­[ÈÎÐÒÈÞ‹÷Á;•X#^Ž hÿ£E­W8ëú—ÃÏý¸1d~Û #é·W« þ—UÕ}P=åÒÃ-Öel®˜ãÀHœq­Ê˜í€@Ì‘?ÿ«høï Êle¿ØËpݰIQÚˆJŒ:‚ÿ®oÔw$qçû¨}¯g)L8ŽwºDÈÈß§|§ö~ª³zä'z¹«\fÿ€!´˜â ?Æö¥Gv:µ˜ÂÉ…~’T^Äv>È«µL©Î8è\I£8ÅX¯4f¢š§ÅŽo4¹î‰Â’¦2(‡N†¿GÌj)s XU˜hÉÖ;U‡ÀÝ|Ô¨³®Ô¨¸nÃáe†#NzØ"ã}J$V£ÎÊòØ”LaiÔÅ“dçIsá½Ø7c‰W lú—8ùpýGGêj¥áŽ=Ùæ“Ló) W„=ð\‘ع1*уl<™ eê1T/áîR‘™‚:vê¯å¤©³©/`ÚŒi?* õ°Môz^üZ²PVW£œ¥úÝ݈Šê’o -„û…q¡ÊËb⤷ªmÀ%p§u›QøÒNÙ˱ŠO?·æªñÊ'Gq<1ˤ¸ü{ïñ@±úKj¦öó!z@ŒØ®Ãp‰gYÛÕñu†ê'p;æë‘0ÿÀ8¡9]Åà’7ǵë(¾DbÉÎWæ1†QY˜øƒ.±™Õg|Ó¥—ð&ý…˜qR°$Ljʤqœ%>“jth!Ïø(C¤¢¯©ôó–Îny·Þù€ã3Çy2×Ñ?[ÜØm†[8ö=ïøàL%ެ–™»I½]wàB^‹v¿Y»`³·=ó§ÅŠ é„òÁ w»¿bd‘f‡Ú“bP¶‹Eñ9î¡ù{@罺Å,©þ^k¼`©.„¹>*ÄÎáyÎ:ÂÊ¢zÑß )·üú^˜t¼ùì˜~%G×]ˆw@Ÿµ¿vÿêžCU”%ºøËÑ!Ôò\ÊÉß˜ìš KB¨–·zý˜>f”œ¯K%¾„µŠpƒ>Fr™”Uäž]xˆ«•M+†,ëÞñâéÁP5ÒŽYnæsíB¥|}2Êm¸’>öƃì)èðÉÕvb5ü˜ÃÝzŽþðÿ7 ö˜¸Ÿt=>JÇ ã3žuþˆ#W¤Ç7Sþù£ùí×~‡û©óÿoÇi‡H#¦¾1×D’9ŽDÿsõú~þ¸)>¾ ·}ëÎ~‡ù{aü‘Ƴ•q}¶±8úò‰ù:ÎÏÏE¥n¦ Bá ȲßÂ;¶_ ôWVhrTÔó‘w,ëS^k{¥´ó !¾'<œ|,¶é¶âÉW‰¤`4JQˆ[F|6E­f<”+³ø#­pK±[\" z_ŽjyéþláÌ+ÊöÒŽOýí–O§ô‹â³Ì›£yâsÅÏôM|‹½¸Ú†‰/eRƒ£Æ—ü³<·.·êÇAäÃŒ~Ù:øx/ øZ™³ŇaÁ+Ót±cMQXYr|JÒìâSOdÑÎ×Kï¾ùìI—šÝÊáJË%U“¨Ž¬ýúRã ,…]¾³?xâ² 2ŒÔâ‹K#½Eq)ž¾Ó*GјåÏK•óÙßߡßÿüñÿØ6~`endstream endobj 6 0 obj 9110 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:10:17+10:00 2013-08-12T12:10:17+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/triangulation_noncentral.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000009414 00000 n 0000011105 00000 n 0000009355 00000 n 0000009215 00000 n 0000000015 00000 n 0000009195 00000 n 0000009478 00000 n 0000009519 00000 n 0000009548 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<62009C6F88F996E1CBDC383E7C114EB1><62009C6F88F996E1CBDC383E7C114EB1>] >> startxref 11360 %%EOF opengv/doc/addons/images/nonoverlapping.dia0000664016516101651610000000656613344612246020026 0ustar dimadima‹í]ßoÛ8~ï_a¸÷’0äðÇëmØöîaqw¸í=J,'ºUì@VÒæîo?’RÇ–šDÕ¨K-`GæG23ß ‡Ãá?}¹Êg·i±Í6ësFè|–®Ï7Ël}ñaþïO¿ëùOßý¸Ì’ì¿‹"¹šÙo¬·î݇ùeY^ÿpròùóg’ßm“rS<»!ÛôäIž''ö¡“ùÇw³ÙnˤLÜgõ§IYÙÙM™ÎÖÉUúa~–œÿqQlnÖËyõTýÜù&ß³Û$ÿ0¿ò¯ùIÝÌÉ“v¾Òöur‘žiòG{ÓÔ¾ŒéÒôuZì7{u½Ùfö‘òîúà‘–vÜÿ;ÏÔOmíCë‹ïKË2-ÞWݪ?|l¯©³­@åUR\dëC,;?y5@$7–œòûyy=ÜÙ¸pù¸pŸpÙöôzS”E’•‡g›Mž&ë µ,nÒî8Ûó$·"öµa±î­¯²²Ü<ÓÿU’o_2€êã{­ö^ÙòëÊû䉖V>gËòòôK éªZ¿ Ôúm¶ÍÎò´©÷Ùº¬ù»ašßÿëxüzOi¨Zk5KÊT¾ÞD\ÜdËtûŒ˜=}¦¥¥Ëú±“çf}ÿ¹—NLõÑžÁöyr—uó??šêYý®g–œ—Ùíý»9Ùœý'=/ëÁþ^&ëeR,gdz߲µýÖƒ#bÝlùaþút¶öÇg[³Dx0]×›™Ò™#Ή2ŒïOÄ!´¡œíƒvÉú"Oï”ÐÂx$ jÁ$цê#A‰–LwC>߬קézéÔe˜‡Oº~e®_¨ëÖ¯õÍÕùõ~wšôø5ZK“žnË»<Ýo9µxUÓâeM»y³+JÛâ¸ÿÍìÒ ŸX+kåÆÊ—óÙã¯íœLc×Ùý—¡õË÷:·×¥êãJº+ë« `ýëŒ8ÑA¥*S„QÅ+•|ထs¯ BˆÀ Ò6̱ýDe¼‚ Ǩ  "`‚ (ˆPš%N¤"¬†pê(‘†¯!\£C6‚šðÒ<ÎFáFë¨R]U÷ûTÖCE€á8YV>`"¬—… „WTba%‘JÐÙtõf^ãe5³ÑÍ2š{ *zY;^–˜ †ˆ¾€éÓX÷C5"`5A dý­W´ÐÎñÑ(C‘Öq>ê:V9dšé¨!;¢úhÈ7r³do7 Eã%G¹qHŒ£GdNC¸cu'‰ 0´›Õ6Îf ±+£jÍ ªÈ£›Å'¨"ª·ÑVP±"WëôT‘cI3Öj€õ¯pá •¨¤–šÐѬÖ>j{ÊãzÊÀÄåúŽ’ôò´Ø·Qì«$‚0¥•gwŬ$ ¹ô¢Ç”YÜmÿÀJÒ:Ð%œùžê®‘„ïÓÙ *‰î¯$…¤êˆ².ŒqH%[Øõ &8%T÷µÚ†Ù¸nq'þQ®Õ[S§’ [’ º¢Ý¶eR”§IQl>·ë ëÝöiž®/ÊËC¹ß¼¦Döñ›ä0¬¸𢇖ÃMÐ#Dïé†ÀÌ G…#E©±¦ˆÔ2'BÕñF#ÞØ4ÊãÖÄWÝ”;ùk“!°ÕÊ%ÞÓM€?ƒrŠË†ÝÀ¦òø©u$À«fHÞ°ËïöQ¸®Š*2Bd„—F{ߥc± d§FÊzCïÔ ªwj´‹±Q»8wk#mÌ(;5MãlxÔ2Rí:¦„‘I"“ ¶£5 |J¿”;lÀîÙ wò!Lj·Ï 2äþ€d×ܲÁ2îžEéæå™Ôé½gZרÅþA€½£)-‡R¾’ÉÝv,`³.›€Üç³Ur•åw¶?Éz;ŸùÀ¡—³ê«KóÛ´ÌΓ]:{}.Óìâ²±»£éÓ—èúT_%Œ]àöY³õ0Ô.svJòìb}•6ÿMYô¥(ì¯ÓŠ[ߥvBç£Ä@$3«ð2ÒUÑ„ƒÛ´Â%uf"T™‰0FbbÓ07“hgºŽžÊŸ×SßhG‡‰!ÈÀTY,¨ I†P#E•ȯ+2@*8)ØlÐ8Î6°)wRCdƒÈƒxËeÓ©*ËŒaèlº:3_pF´ÒV?1Å(Ùt ãlȦc–0$ºŽi¡ãIdƒá’ÃF1z':í@—þcÝxÔ7x@B«l‚-v%c*F1b£UccŠQ ìŸÊ!™à>”`LØL¦¹–UЈ…¶~€ÑÌ­$$ ~¼²m˜ÍO®\¿„¤&æ¢Å\´˜‹Áô ç2«Ž+pv˘Q—Óa9Bøc͘Ç2šÆÙ¸» Ì˵$+iÜ2Ž‹­á¯„ ½˜éVÂ…Ö.ÜÉ™„·SqÈr2èú\Å0lä‚1 3ÑÀ‰h-A $¢)fÄ‘ÛÓ&p"Z…„ÖX \ì +ÚU×qŒ”t•g¡*èÙ´G(g%…X+bs…ͱ+vt«¾[·ª]8#[M‘­zŸ;qŒ!9x€Î·r¾Œ­ $†ÇVj¶’™·ÏV<ºVcºVíÂÙj‚lÅé€\<@g3A*$J´T>„IôÈBLª¢c5ö`³dF¦š"S±6YE” »è‘Rø«­­€%XBt©FÞl”ËHSÓ>‘Çaˆä*ôóxP‚ œ\%j$ Òq(¥‡ œt–mÿ)ŒY¶1Ë6fÙÆ,Û®®kï㊠խ¦Ì5Hî²1¹Ð¤]®ù‹Ê +ð˜¾ëíÈ‹ì_‹4ý=-²ÕãòúÞmýÅrPfÓw¸´n•ÇXEbâ>«è_5‹3á« b*hÕ,P5uI,S¡6¾~p5á£ÂCÌ_ôWGõW÷¹)€¿Ú"ú«Ñ_íläöÀ:޾¾ a¼GÂ8‹`°zʘI›„þSmÂè6aµ nV1†mÂØ6A PÓ¼µËGÉÂVp—°VHB¹êî²dãß=éêCLa´ £Ú„Õ*‘× } ¢Mˆ6¡³Mè}šH ÀÄ6A&k$oQˆÕûiÛ„A¦0Ú„‘× ®*}àuBwˆh¢MxÕµ|ˆKx4“Þ³EC1ìeè¨*$!^€" ”9â– +ɼæžæq6Ü´§ˆDÕsJâEbñ"±x9I§‹Šž¿œ$ø•²mtk¸n^)wó˜"œò©%‰sT~‹Vr±N(•¾(2W]ë¼æºùæq6?ŠÒ÷‹ŠlÙ6²íàlËú°-|› ¼EïÓr®j1×Α´Zæ=ƒÀ–Òz\¥§P+óöú/³˜È7ÂÞ-òóø¦Ç'Ø~¡’U74iÖ/´BBÔÆq•á”՞ڄ㱃LaŒÇÆ\¾ñØl aèzÅm«‘@eп×aÚ6¡÷F›sù¢Mˆ6a›Ðûh¢ß4“þ(˜DÔ&¸]° ´µ èx€»í:*ù”mÂSmBÌå‹6!Ú„l‚ …ƒ #Ø‹¦Fr6Á'U¸½»©Û„A¦0Ú„˜ËmB´ “KDï߆ø-Ȇ 0.¯ 7T/ÜuoŠYXMXçj{/Î*9`ƒ{ψ»þ I×:Zß0—„Ò”¥"XšDçØ¤ò$J>P”““^yØJrÄÕ÷eä( ÇTìíg”±@ïÈzä1`âÁS&‹‰MÔT½Ï“»´øø®zcÿ]ÉÕÇwÿÚ ¸cäopengv/doc/addons/images/relative_noncentral.png0000664016516101651610000021731413344612246021045 0ustar dimadima‰PNG  IHDRÄÉ A¸—bKGDÿÿÿ ½§“ IDATxœìÝw\SWðß͆€€( ²êÄ N°¢ÅY­[k­XwÕªµ®ZGÕjûÚjÕÖÕ*Új¥jÝVÅ 8\ˆ ‚ÊÞBÖ½çý#aœï'ÜÜ›Üû!yrÎsÎa! (Š¢(Š*+ž¡ (Š¢(ªz£ÉUœ:uÊÐ!PEÕ^4™ ª½ØØØÁƒß¼yÓÐPEÕR4™ ª½ 6¨ÕêÕ«W:Š¢¨ZŠ¡˜Tµ–àìì¬P(\ºt©{÷ˆ¢(ªÖ¡-Tõ¶yóf…B!‹¬\¹ÒÐáPEÕF´e‚ªÆÒÒÒär9!ÄÈÈ(??ÿôéÓ}ûö5t\EQµ m™ ª±-[¶äå幺ºhÑ¢€o¾ù†æÇEQ•Œ&Tu•››ûË/¿©œ`(Š¢(:ÏU’¬HöÔÐ$ q§Õòd®àPüeM~ i:Fd˜È^x¹›ƒ¢(Šª|4™ Þ¢ŽÏÞKW Áiñ§ªàÐã*1ã{8Ö­[ײeËúõëÏœ9óâÅ‹oÑ’¶LPEÍA½­§ÀÌ…—ÅP¤“Øã*ça¢èÃ*¢é§úéãÈÊÊ:räÈΟ?¯M „BaÏž=GŒ1dÈ’ŸK[&(Š¢ ‹&T)0hþ™øú7ùÚ{}UÎÃDQ~*k7~ÝæüòœX&“=zôÀgÏžÕN3% ûôé3bĈÁƒ[ZZ–æ$´e‚¢(ʰh2A•ŠóPá­ªl =Œ½¿M™ÍuûÙ¸<ç|ðà——Wjj*>ŸÏ0L½zõZ´hѸqã´´´ .8995iÒÄÔÔ´äóЖ Š¢(âóLP¥²F¾C7G5ÃȌq½¿|½QQQãÆ»zõ*ÃÿR5r~T*-xL||¼½½½ÝóçÏË EQU&4™ JKÏîž[0å¥ëT±ÛBIùOKÙ±cǼyód2Y½zõ&NœhjjýB|||±ÏªgfÓ°ž“}]g;s'žåÿÎÌ6™=¹‘^¯m¹º](Š¢¨2 Éõ.M“Çý§Àð0ô’©IC½Љ‰?~ü•+W†™=µüa詨TMlŠ&6U›¤‰Rp²—Ÿ.Ú9Ÿ+“š”«ç…¢(Š*šLPï 9Xóߨ<v^ï]ºŽ†Ø“ꛫR[ÆÚMðìœZžLì{ Þßh̼cÇq›6mZ°`R©trròõõõôôÔz諊>¤ÕaxBƈMÉyö(,**::‰ ˺§º;Øtá‚ezý‰)Š¢¨·£ÉõnŽ(ËxÀYÖ+`Ž<;šëµG*6gžS_˜"ï¹Ã¸¡wY&³ 7n\hh¨@ ˜7oÞÊ•+E¢Wê2‹ÇTw6(òS ðøØž4-P¶#0kõj,^\ÞŸ¢(ŠzGtÒ*êÝ 35•j47þY¯?EQõ´e‚*¯‚Ag —Ïh5]Üjº¸„Ç— éš&ä{Ez ÀÚï¾ØÈª}ÑÙ*$VŒMGE3¾µ;ÿÌ™ë,ËvìØÑÈÈÛ¯üüzæç—õG)Ι3øå##B!Ä?ÿèóüEQÕM&¨*!3‚½ù"1HÀ¤!Ïm¡Ä¡ŸL1ÖS¿¿“/J¾èã8̘??‰¿¿ÞÂúñG|ý5ðù=W¯âɽœ¢(ª¦ ÝÔjµ§gÈO%såÇû˃4¢:LÇo%CΛ:ô/>“øæ›oÌÍÍøýÍ@@@€‚‰2áá¡JqÕ×W‘…‡cáBÝöäÉøóO¬]«‡ÓREÕ84™¨Õ Å–-[:wîÌ0Å}tW0u ]§8ì•ý¯š'€ëçâ¡—M›óÞÝߪÔäç!ÂÁLÝH´sh– {÷î._¾ 444??¿yóæ6nÜèìì׳'€zÉnß.ܶ²33 ª‡3SEÕ,´f¢ÖÉÊÊÚ¼yó† ÒÓÓµ{Ú·o_™<;¯]«ÐŽõ°é p_"©×¦´k‚µiÓF*•FEE¥¤¤hû8´þþþóçÏ×h42WWL@€")IR¿~¹ÍÌ,ÜÐÿŠ¢¨7¢-µHjjê’%K–.]šžž.ÌÍÍQ‰ÉDÆöì§y&ɳ£8ÓÆ¼ž;ûúIKŸI]»v%„h«/===ƪV«W¬XñÉ”) C­ö_° ¼áj4å=EQTí@“‰ZáñãÇ>>>ööökÖ¬ÉÉÉ6lX«V­4\.СC‡Š@Ï]ž!?1P–¤‘X2]Ö ö7møAY–ÕVH$Í›7ÿè£rssÇŒóÍ7ßHëÔ €åõëew͸¸àÞ½Â=ݺa`o_ösREÕ\4™¨ù¾ÿþûV­ZíÝ»W­V8ðÚµkaaa7V©TæææwuµŒ„®Sí%‹=¥æ áú¹xÈyÓ&£E¼²öh“ ÿÌÌ̆ ~ñű±±;wÞ¹s§¶Œ´Éܹºdf‚eËx |ü1ll ÷øø`ÉÌž]ÆREÕh4™¨ù5jÄqÜ”)S¢¢¢Ž;¾sçN##£9sæpss« ¡„ÅÃ]ÊCïçÞߪd•¤ÉhÑ‹¦n $"³r]®S§NB¡ðáÇÁÕ«W6løï¿ÿJ$í$nnpvFjjü¿ÿ–ñÓ¦aÕ*¼\r1y2V­Âüù剜¢(ª¦¢ee5ßÈ‘#ÝÝÝ›6m 44tÆŒ6nܘ˜˜ `oýŠ=¥¾³^‘èßYà¾XbÙêj#J •JÛ´ibjjúäɉDòÏ?ÿÔµÖ2ÂÙ¹ittÈŠvÇëå¢EQT hËDÍ' µ™Dzzú°aà ń &Ož|óæMîîîú½\J({j˜ìò yv gÑ”ßûOiŸýR}eZÚ¢¹¹¹<ﯿþêÔ©S‘˜Œ }B‚/JQE½ m™¨-8Žûì³ÏâââÚ·o¿eË·nÝàææ¦¯Kä>ån­SÄžVƒÀÈŠi;GòÞH£Ï,B§K—.ÚE‹ -nâ»1cðå— 32‡ÆõEQõÚ2Q[¬]»öĉ–––‡–H$‰‰‰ æææÎÎÎå?¹*‡¯È?â{J-0bÜH†^2m2ºB2 žžž à 6låÊ•Å?B,&| ‚® JQUñh2Q+œ={véÒ¥<o÷îÝ7Æ‹f‰víÚ•³ú’UáþVåáî¹w«‡&£ECΛ¸~.WàüÜ666Ó¦MÛ·o÷Æp„‹ €ä?þ¨¸0(Š¢(-šLT¶¸¸¸Í›7Oš4©Y³fcÆŒyùЉ'LMM§M› <<|åÊ•cÇŽíÔ©Sƒ òòòîÝ»7räHKKË¡C‡ÆÇÇ—òŠÏŸ?;v,Çq .0`€vgÆ ¿üòËáå©O$ˆ>¬:Ò37tB™Eì{ >:mÚe‘qýÊxQmÞ¼Y$•ðçY³Ð%?_““S ñPEÕj„ª\¹¹¹111“&M`aañò¡ƒjÿ(111r¹<66ÖÃÃ@=Ž9Ò§OŸ={öüþûï 4ЦMFóÖË)•Jm}bŸ>}X–Õ×O‘¬>1(w·CÖn‡¬cýrÕú:³>uè@rìXŸÞ¦ t·€½FFQU£Ð–‰Êfbbâèè¸zõj™™™Ïž=+84lذѣG¨S§Ž‘‘QãÆíììÔ«W/88øôéÓcÇŽ0aºuëܽ{÷êÕ«o½ÜüùóoܸáààPr§@éåÆqç'æý72/í.kbÇë¾ÅxÀ “U±’WÝ»7€;«W:Š¢¨Ž&†ammíèè 22òåýƒ rww/XÆS›.dff®Zµª ¸¡U«VÚ'Ož”|•½{÷þòË/"‘èï¿ÿ®[·n9cV¤“k‹óxç>¿ š0n $ƒÎ™8ô2UõE”×£«àà\½÷tøù¡aCtíŠùóѤ ¤RŒUö 7)Š¢ª¹ªú9P 4oÞÀÓ§O_Þùßÿik&ÄÆÆ>þÀ²eË^.“ÌÍÍÕnÔ©S§„󇇇kOµ~ýú×gbx'¬w6(½Ÿ¹_Eš&vÅÔõs±À¨«,ËϼgÏ,©ÔŽ^XØ;?9<ÙÙ…wƒƒ BtwGŽD÷îP«±h"#±oüüpò¤~â¦(Šªnh2a0ÚQ/ws<{öìÎ;cÇŽÕÞ½téíj $š5kö¦“çää :4//ÏÇÇgæÌ™e’pˆÜ¯ú·GîÝJœ8ô:cÚq™‘Ø¢J§: cþÉ'¤/¾Ûƒ‚àêŠØØÂ=óæÁÑûö½ò0©ÚöžAƒ ¾òxŠ¢¨Ú„&ckk‹W“‰Å‹oÚ´I(Ô­¥©M&FŽYä‰gÏžФI“’‰É“'GFF¶lÙò×_-s„I×5'Ë®-ÎÏKä,]ù½ÿ’vßblæ\^3š>}Dþü3)hT( RÌíÕÑ7¯àñÀq厗¢(ªZªŠusµ„ €äädíÝ'N4nÜøåFm21pàÀ—Ÿ%—ËOŸ> `îܹo:óÆýüüÌÌÌþý÷_©TZ†Ø2#Ø›ß)ƒ4LòÜJú Q#Šôí«d—ŒŒÛÿý×¾_?C‡CQU3ÑdÂ`¬¬¬dffHJJòõõÝ¿ÁÑ'OžÄÅÅYZZvìØñågmݺ5##£M›6'N,ö´óçÏgÆ××÷½÷Þ{רòSÉŸýT„…¨ÓöKqÓOÅ<Ở¦ÊJÓ[·¶½{×õ¥ Š¢(J¿ªS“u caa 33S©TN:õ§Ÿ~ s»‹/ðòòzyÂ"r¿êˆ·ìþV¥&Ÿ8ô~tÆÔmDl^ ;6^7p ÙáÃI¯œ)ܾèhøú‚eñý÷Ðhpê>ÔÛ%¨*¬eKL˜€G˜ŽŽhÓññàó1y2¢£‘®]qö,† ìYP* 1U•BöìÙcè(ôŒ&cbb ))©gÏž={ö,rôÂ… œœ<`À™LP°ffß~ûíÅ‹mmmýüüŠm·(Öó šcýr¯-Η'qÖî‚›tßb\Ç¡½05Š555á¸{›7ëíœÞÞdzg7|>-‚Fƒ³g ¿«RUÕ7߀aŠ¿ñx01­-ºuÃ_àÜ9”P¶«]m7:x<´hí?qX Œ&MÀÉ Jå+£ŒËæúuL 774h‘¦¦puÅôé/ʷjÕªÙ³gs5«d›ÖLŒX,ðÝwßM:µÈ¡ÈÈÈøøx33³K—.EDDäççÇÇÇ5ÊÇÇçMYÂáÇ׮]+ <¨-í|«ŒlÈ]•¥ic^‡¥’†Tó.7  _ßÞjµ¡¡ oÁôïë×1o^áÎ>€ƒ8™™¸u  ÄæÍpwÇþýpq)æ<&&°²‚¶µ+"íÛC"€€ØÙ¡ l:&––¨W¯¼aŸ8?þÀèј7ööÉpö,6mÂŽص Ÿ~ZÞóS•fÿþýË–-#„þärœ:¥ŸKP***jôèÑjµZ[0lèˆô©f†èZ­¾uëVPPP``àÕ«W ¦…`bbòøñã:èý¢xµú²S¦L¹wï^óæÍÿøã—gÝ.‚°x´Gyw“R™IšŒµþB,mP;²I>?ÊÅ¥MX˜êðaL˜`èh¨ªŽÇC›6ºâJozÏ77ÇáÃøûo¼XK‘‘HN†v4wDV­Âñãzèã°x1^_§ÏÞ^·¯‡KTKgÎà—_ŒŒ …8ÿüc蘊—œœÜ«W¯´´´úõë'%% 2tPúD“‰â]ºtéÂ… W®\¹yó¦\./Ø_¯^=OOÏ÷ßßÓÓ³]»v¥¯s,½¸¸¸¸¸8†aÚµk÷ÖïØ±ã¯¿þ’J¥~~~Õš¯‹=¥¾³^‘ðé$è°DbÙŠ¯Ï Ktì6lÀ±cxs€ÎqæLLê•—g°¨jE$*Ü~Sœ½=¦MCëÖ…{®\…€@€¨(\¼;»âŸ;s&¶ly{|06.æhAP骤jœÄ×_ŸÑ£qõ*Þ¶ö¡¡ÈåòÆÆÆvêÔ),,Œa±XüèÑ£ŒŒŒò/ÁXEÐd¢x ÃlÙ²%##€T*U©T...=zôsæ¼ýüƒ¶+”ÀÁ¡¤£Ú±$jR_i…‡cáBÝöäÉøí7øùá‡t{ºwÇ•+0`Ž7L„/p7nܸ›7o:;;/]ºtÀ€-[¶477 îÛ·¯aÃÓCm¼Ñn‡¬"·sãdG} ÷?;_!Uu=ÒÎ )zùK P§N¾}û®ZµêòåËr¹\WÌÌÌœ7ož‘‘‘öBÇÿûï¿ßôàÔÔÔF˜9sf±È}Ê^šž·Û1k·CÖ÷ìˆ}JN£Ç`ß":š  +akܘøù–­¼«R£F8òñÇŽƒªJ(À$„Ÿ?nܸ ¸¹¹½<%%ŸÏoѢŔ)S|}}ccc+*Ž×°,Û¿*•ªÈQe6wc¹|Ï{Y»²ö6˾ýs¾:¯Â~G¯ÉÌ$³f‘ˆÄÔ”¬]Kòò*íâ%¹;v,îµicè@(Ã+6™`Y’œL ŽŽ…‡&O.í9@nܨ¸¨uär¤û¸´³#Uø«¢>(ü#]¼Xôèÿþ§;´s§b{Éo¿ý@ œ9s†âíí ÀÏÏïСCz÷îmØðô¨ê&„ËäÉÄå/^ùDâ4ä@Çì#½s+:Žã–-[¦M&Ož¬R©rssÏ;·lÙ2ooï‚V­ Œ1bÆ !!!WŸß+W®`eeõìÙ³—÷k”$ì7Åþ¶Ù»²|³®.’ç%VÞw¥’¬]KêÖ%áóÉ”)$>¾˜‡¥¦’èhÝp»§OIHIN&„GȹsäéSB¹u‹øù‘Ç !$0lÛFîÝ#„«Wß¾IÎ#ÚÔîÙ3B’’!$åÊ=pu‰Z]‘ª(’L{33#«W—öKJ ññ!ùö[’ž^‘Ÿ9Cø|''²`IK«ÀkUiíÛþ©Š=~\w(0ÐÁÒ6Klذ¢P(Œ†IIIyþü9 ‹ ý¤¨LU:™È~Âj[éw;díqÉÊK*ü·~v^½Û!롯²r"Ù·oŸ¶NÂÛÛ;##£`¿Z­ Ù°aÈ#, Jº_ô†x{{¯]»6 @¡Pè1˜Ó§Oóx<>Ÿþüù½yrRuØ+GûëòŸ ËŒ¬Ô¦Ï HÛ¶ºÿߦMɵkdùrâäD|} !dæLM›!ä‹/ ·gÍ"Ù¸±¤íÙ³ @6l(íö—_€üô!„Ì™S¸ýå—$.ˆüãí~íô«W'']ëôÖ­ÄÛ[÷=õÄ ²`¹t‰BîÝ#~~äáCBIO' $?¿¢£T*’LôêE¦N%ƒîaZ¤¦’Çß~{= $ùë¯ Œ­zhݺ¤d"2Rw¨ d[—´o"„h‡éµlÙR{WÛOýàÁÃ…¦OUzd`ž½—®ZÓ âOUÁ¡ÇTcÆyh%ÍØ8zôèóçÏÛØØøûûwìØñÑ£GÚýÀÍÍmöìÙ~~~iiiÑÑѾ¾¾S¦LqrrÊÉÉñ÷÷_¸pa·nÝêÖ­ëéé¹páÂãÇk— -³ØØØ1cÆp·bÅŠ‚I¸“ojN•]ž!ωåê6ç÷þSúÁïRó÷*ïë燾}qç£M´k™ 11HI ›P¡[[89éö88ÀÍM7²®ysx{ëªßÝÜ0bœœÀÃS¦ U+èÒåíÛÎÎðöÖ=·~}¸¹ÁÖÌÌp^bàÑúõÚ2xm…üó爉Jaað÷×ÅüßX·aa°cFŽ„v±°+`k‹mÛ`Ñ"ØÙéæ!سãÆéjï¯]ÃÞ½ˆŒ€ü|ÝNUYS¦`ëV>Œ‚5z ÁÔ©Ðh*êŠË—ã½÷Þ~óñ)úD++…Ó`ÔFkÖÀÅ÷îîéÖ óJE«£#„BÔ«‡W¿ãD÷îݵÚ—¼¼¼´w=<M!gÎ;t]9yyµ²†ÎpÞT€yû¶®A{[¾\Ï×MH NN$9™Ü¾Mþùçí·+WŠž!3“$$DÏU'¿þJ–,!66…'²d ùá‡WÖ²e1“†T¯^½øiËE ¹uëÖ•+Wrs+¼³¾rTõd‚pä_|"ê ’¶M±Û!+ýA%Nx!77wðàÁ;wΗfœ‚2‹"ÃJµeÛ¶m»ÿþ[;Ïf̘ÀÙÙ9333?»ºH¾Ç%k·CÖ_®Ùa¿½R j(J%ñó#:éþÇ…B2b¹vÍÐaP©ˆ™HLŒ^Î'“‘gψöÝàÚ5²k‰Ž&„mÛÈ'Ÿ«W !düx"’!dÔ(ýû !dôh½{ !ÄLJdß>BùáòñÇ$(ˆBnÞ$.ÔT½K*a4Çܹ…û=wvlÚD7&åì%;–$$è) ê«M›’º9ª¥RYP0aèX*D•O&yô§² ™8>0—òï9§†,›Óh4©åxwW©TeE¦+±¶¶0`€¶ÌB©,Z²{÷nÆÆÆ·oÞ ûM±¯®ÊòÆr¹"ÃðiÄË8Žœ>þàÁƒÐ& êÖ­;dÈQ£FõìÙ“Ï/Õ"G*•ÊÂÂ"???99ÙJ; §Æ©º&v¼F½„qÿ©0<4#*ò€Ü§Üýß”*Ic‹;AµÁ*‘¢I¾©I á§Þîh/ï`@$€\˜:2ÐÙ‘c;)Ø@…&DÉ^Îg/çë~ä|ÆÓHà!á{JøíÄü*=ê× ò¼¼¤×¯_ûæ›.5"™`˜Â‚//A‡ädÝPÛ‰ñø1Àq¸yJ¥n„áøñÈÊBJ ŒŒ0p LMñÛo03CDìì ¹0[Å9y#FÝùÇøãÂUµØÛã»ï WÙxòãÆA*-L/ÜÜ : €ÇC‹ÐŽÔ ƒBÁƒ¡]ÆÉ J%²³am­ŸøW­Â×_ÃÝ}¤ŸRo’žž>jÔ¨‹/r@(ÚÙÙuêÔÉÛÛ»I“&ÎÎÎ¥Ì$„„„ÈårWWךšI¨-’ƒ5ÿÊ`ç%ðÞ%-rT•M„¦LÎîˆwî¿K«WË« iwÙ¤`6å¦&%”ÕÈ ÿ"Æõyõ;ñ“®³òd.Uó´çOíGŽ¥–rKÉ)4ùìU›Á>±é(æ{HøžF|‰Àˆ¶Y¼$/(Hêé™Ä0Ò¬,Ó:u Ne“ˇæÍ¡P`âD¤¤àÜ9äåÁÔ"ärpLL VC&ƒ‘¾þg PêwÎÚÂÚ6à“Ok×ðÙg°y3Ö®ÅÓ§ºçLÁáÃHI)fqª\*¥eâñãÇ>>>ׯ_À0E?.A£Fœ^Õ¤ISSÓ"çY³fÍ’%KfΜ¹iÓ¦Šˆ³*¨6º6u[ð3°ÍÆÓ\(2«fŸ–y \ÒuMJ›¢ÉŽá zpxX»ó­ÝÖîüzmFõ˜Ä MÌѼ<&}q|ÇÛ-B”™vXíÊŸÆ ã)á{Jø Ì FÍ*Ø ¨Ð1ch&Q]½÷Þ{W¯^ݱcÇœ9sär¹µµõСCY–ŠŠŠŽŽ~öìYLLLLLÌËOÑfίºpá^š½ªFª6É€'«s«+AÖc6%”M Ô$‡hòS 3\¾„±îÌ·vçÛtXµã Œ_ù°ß¡ðÀø”š(²Ç'Ë”Y¤ß!iÝæE¿': yNBž©@"KB^$7•l¨’ U²¿dëæ!ỉùž~{q-Í,ꌅ­[…gÎÔÂd¢XÜÝ¡­-kзoëö …X¹R7ä£GxúÚáÌQQèÖ xòiiøñG¸»Ó}P³YY!3Û¶aüøÂW®`ëVݶ6W[ºÔ±QúÂ0Ì”)Sºuëæãã²}ûö™3gž>}Z,+Š˜˜˜ÇGGGG½ðôéSm†qN;cîKçéÖ­›¡~ŠJPmº9J#;ºjusp¤ÝѤ„°É75é÷Øü´Â_µØœiÐU m„¨Û‚ϼ¡9ã!{¼¿L`Ìì±s6àÄ… $þeO¹÷7‹ÍK›äqä¶Jפ`3ßÐâ)HjMf¡8xP2bD˜DÒ2/G¿6–ŽZ¸8äç£U+ܺ…éÓñÞ{Ø»çΡwo¼ÿ>._Æ;˜<~ˆåË‘—‡Ü\Ô¯oè¸+ÌðáxðÿÖ­u{"#Ñ´)âãak‹ˆ ??´mkÐ(kªÊ*À, ÑhÖ¯_ÿí·ßªTª-Zøúú¾<²£€J¥Š}ðàÁý»wSnܸ{éRB~~À0ŒR© +i ˆÊW%>tk’—*(ÙÔÛ¯@˜Øñl:ò­;¬Ýøf.|¦a~Wp&Þ"òòòÞÿÖˆáƒ'@F8[·¥øø—ò {CXà‘6±P°A 6F]|oH#A½Ýf!ùðÃ|†qU(ÂΞmÝ·/­-lmqùrÍ,;Ô¡..ºíöíqýºnÛÞ‹A;œ9$!!hÚNŸÆˆ3þ‰¨(ܼ‰.]ðêt*Õ›½=¦M+Ì$\¹ 8QQ¸xQWKéYx8²³ ïÃÞƒaÀÏóæ¡aCxxàèQÄÇcÀìÛWΪ@°`Á‚ž={úøøÏª]yB¨Ú :0Uϲ¢ØÝYÏΫ+ùºÊ,îÉIÕåòãs}³ ¦ÄØí˜u¤WÎÕEò''U//yZJ²vK–¯sVN;räHÿý·öPøN…¯sÖýíå™/^Í“©¤)<žË„ÑÙˆ*¼9ÅåŽM–oËVÞW²Õc:‹w”¢ô[»–Fl,Hýú†ªÚ“ÉH@€n ê­[‰™ÑÎèóÓO S§BȹsdáBÝ\ã5Œ™<ÙÐAÔxÚ…S_¿i×ËÑ3†¸»ëƒ?r¤pNY}ÈÍÍ:u*Ã0¶o߮ݩÑhŽýûïÞ>"ÞÞ„ÇÓ†ÄuíJüüv|úGq»cæjí¤J@[&ʨ„ J«W+(Ë|‰G{Tœû Mñ¤R)€¼¼<í!3g>u^y»¨lŒ­@0P*Ä2ŽÜyѨ`cÔ\ŒšÛ›«`Ãg:ˆuC:ˆùâêÛfÓ§1i«Ï>Ú£G'âþ}pu5pxÕŸTZØÞ33Ó\­æ¶ow]¾Ü‘eµ—– d2w.ãæ¦Ê!÷æîPWd—Î>9®vT3{:h2Qj/*(µ8sŸrGøbXw¼©‚²lT¹D»äºëçbE’ ;/Áó¦¦y PˉPª‡+š¼¡7$ ŸÕp'äšr  2hý¢7¤§‘À²õ†(èÞÑÑP«1m>üÊãÇSbblµ k—0§ôJ›Œ‰‘#u{ ‚©)úõ€ pú4>ý¾øÇŽá·ß0d¢¢`mê5n71QQ¯ôzPUŽ{ûÃÞE¿~ýúõëç;v¬éþýƒy<¡Zí¤ÚØHæÏ7<ÙäÅk7r¿*]žÀ „~¯hÔK —ψª¦†$©·ÙgçÔ9±€(“ohêwØu/ïOG8d„³‰Ašä›šô06?õ+(Ë,ê€J-#Öî‚z­ùx-™`Ú˜§Ì"óäjzÿ%åéõ/ÉZŠx-E¢)u AC Ê,n76ÄSÂ÷Zˆªöœ ~ø#GbÆ ˜<9ÎÌÌ!;;lï^ÛG MC‡X+xyÁËK·ýÛo˜8;À“'HN† ̘óçqò$úôÁå˰¶.œz²jJMÕM©yò$\\ðê~T¢R©ŽìÚÕ68¸ÉÕ«ã=À‚±c1{¶•v.³‹G{T™l A‹f¼ÌGÜýmʶsŠ™Á¹º«!É„U;¾U;ý|ž—¶‚ÒYÿ DNƒðßU\§èJ{´É„\.ùa„EÆŽS“Ü8Î̹‡$Ø ˜&Â&B¹¹¡dóÙP%ðjoH}>ã^Å{C†ÅæÍ˜6 Ó¦¡Nº>>Ø´©sz:h˄ԯtÛçÎáÙ3ÝèBÀç£eK˜2‘‘¸yîîØ±ÖÖðö†´èÄufe__øú:ª"åççED<ùòË~—/kç¥â5Êúøãºsçê²àW==«ÎKàd’DdÂoë2\|suþýí*—‘"»š6ˆ¬†$å¤Ê&É!š”61H“ñ€-(€ó÷xÖk7¾±M%ýùcOªåIœ™ ¯¡·®wíõ– K¦Ç6c£zŒÔ–G8”fxHù™òo#·‘€† B­ë ¹’ÏÆ½ÔbÌ0íÄù¤ÚWZPU_ÚÓ§~}Ô="¢¥BÑà扛›Ãš5¼>¨ûæ±åþPÈ7OF2ê lë3N cŽªoÿOÑígãJ ¿2ÔÞd¢*(ˈàþV%€Ä#?ñZ2@Û Isý›üþ06oR©3 ˜’zC‚l‚ÀšŠxÚi²<$‚–"C§ä‹!+ ?ü€¥KeB¡IB4kI l{¬¾´îøü¯û¹¹˜5 ±±°¶F|<Ö¯‡™|| Tbüxxx`Æ ÆKUþþ¸}99ðõŧŸâ‡ ÑàÔ)ôéó®½eÇ×­û4=½Þ¡CÓ³²h,,³fñ&Mr´·/ù¹i÷ؔ؜IÏŽ`Áo –·…’§ç41GÕMǰÖî5j‚úÚ”LTne™%^Õd>b¬ça…׋m™(ðä„ZÏ=Ü¥êò½!,¶7$HÁ)4TÜ•®7¤Ÿq{ÑÒQÌä—ýý÷HLÄÞ½F|> ðA‡rT¦¦X³F·mlŒM› “ÏÇõëØ¿aa˜1ÏŸãóÏѯM,j1oo„‡Þ]´‹½ë9X…‚üxôäÉ>ÙÙ †É騑÷ùç&cÆ@Tt¥Éb=Ú­à<\˜¸J[3a§–ãú¼–“Ew7*CÖä÷?dRš‰‚ª‹žL°‚²Ì´óg7+æ¿ôŠ-9™è¼RbÑ”×bBjí-ÒrWÅj[,.çkYRÐ"å1mEºÞO#¾E¥õ†ðxؽ*ÿÀÝZ…_­XX`æLÝv“&صK7#Ñ•+8yfÌ@p0,À¨QøüsƒÅIU;AûöEÍ›7\.—æätr‚¬‘#.]Z§Y³ÒŸD‘NbO©¬?”)¾Q˜HÌÄŒ±Z-'‹#÷«ÒÃØŒGìë«"T_50™(¡‚Rj˫ߩ2*(Ë,ã!Y#0fš}%ù-9™3-'‹Apw£RTÍÇW¡¬€€›˜ï&æÏ6^í ¹õZoˆ6±è&á; +¸7D›O$'ãÒ%©ÖÖµxɪêÍÊJ·b'€Þ½qà€n0Źs¸tIWV{ø0vìÀ„ µnª”žÇÅeýñ‡ëÕ«]ÏŸ÷ÐÎcѶ-¦M3=úõU@ߊS§Á"µŒd1±l,lñbf ¡”yƒ±Ô–gÚØÐ¾z¥K&V¯^ýôéS ‹’=gΛâjV îå Ê̇,§yqÀ@”e¦?Ûe¸°ÈÒ%'ZI74w6(øb8|(2²®ºÍg/÷†äp$øEoH ®7Dµ=ðO#vM²Nb¾°"~ ‰ÇŽÅ9;7NM=üøñÔ ¸UÉêÕ+œÐbút´n­›Àûôiü÷zõ€Í›áïY³Ð³§¡Â¤ª’ÔÔÔuëë×k{:c㈭ZeT¦õ>8Ž»páBXXØœµsœ: A=;äB«ûf[¿K ü¯û‘¼¼¼¼¼¼4MÉöññ©:ÉD^"—t­T«x4Ìw—È=9ªbøh9©hÓBi’‰ú­¦‹­ÝU9“(¢ÎzC.åkYòLýL À„Ç´)h´0â›ë±7ÄÔôÑæÍ™“&I´Ã©ÄÂê¶¿û½{ë&´8zþþðñ€9s‡%KðêT­ðû÷{ËåVJ¥ofVgéRÓ‰›š›—ùœIII}ûöåóùŸ~ú©••U||<€úÖvÈ…:ìܹS Œ7N;wM¢K&<<ßÈȨ[·nÁ+ ”3‰jRAYfóg›4,Ú‚Ršd@ûùŠtòp·²íIå Õ—"½!1j.ðÅ*êU\±½!Ýøåý!ûŒ‰þýÛÒõ½j´úõ ;8vîÄ•+ºf‰'…%K`Ò$…X²o«Ó§ª·ðÀÀFÿýgzèÐGp<oÄnÒ$;oo”{ a[[ÛÞ½{Ÿ>}zß¾}³gÏÖ&¶ ìgI±_þñe^^ž‹‹‹gÅ/sZÉ — '„ 2äèÑ£‰D¡PpqqYºté˜1cøå[l @n§–“2›”PA)2cl=ªbeÙ¨rÉÁ®¹jùð¨‰vÀçËâããííííììž?þ–œ$KcÛÏ—´š^µŠ'Ê,…%7l¨R—[(^š˜¿ 7ÄSÂo'æ—íàÙ³glÑ¢EŸ>}ô2U=DFâêUÝøRKK(•HNF½z3Í›cΜ*7;U.wî„NšÔ$4T[¡´±‰îÓ§Ùš5<½®îzðàÁ#F¸ºº†……MžðÉÏyÝK ;vìž={ôx¹*¢0™™™Ù¶mÛ§OŸ><**êÎ;5j´dÉ’ &i¥(½äš‹Óä|13à¨IiZà_® L»Ã¾¼œUÕ¯ ,³;•7W+l:úúóî•••eaaannž™™ùÖS%ßÐÜþIùþF#ãúÕªi¢tÔ÷^ô†\Èפ³…/SÓIÌ× é*á—º!qëÖ­Ó¦M2dÈáÇ+&jªªã8„„àÎL™‚ØX8:ÂÜ©©à8Lš„ž=1nj\Ëtm‘s}æÌ·oÛ%% @¬³³ãÏ?£ÿr®K^,•Jegg—––ºdÉ’ÿþûoß–£ç—=û=m¦µµõƒ,--õ~Qƒ{%™УGBÈ©S§rrr–.]ÀÁÁaÑ¢EeH)îRÞ\­ ,œ »®5æ¿á«rI”.ÎçröîÝû©v]»§h2`åʕ˖-³¶¶¾sçŽÍ¡C‡¾ùæ›ÈÈHŽŽŽ .œ8qbi:>8 n|›¹_n_K\§Š‹LÐñ¦ J†‡º-ù <Öîüz­FV5ÿë@ÌQuÀ—r3Þ೦ošÆD$©Õj•J%–jÛgçÔ§É-šòû6ySWÃ$±äæ‹Ä"DÉ*õÝBÕBII8xR)ÆÇ`âD „#Gtý#}ú AC‡H½N­f ž4©s^žö 5ÖÅ%o̘ 2•2ÑíÍ›7;vìhiiIÉÈÈø°ïÀ“ÿo]烻Ùþ•puƒ(&™à8®OŸ>þþþ^^^þþþ|>Ÿã¸C‡-^¼8** @óæÍ.\Xr-…*‡\ž!OÔð%ŒçÿŒ>Ô}þeE¾¹‚Ò½ÚWP–Á±þ²ÌGl—ïš|üƹÕÌÍͳ³³333ÍKWi¬‘“Ó#ó\† ›V4« ä„ÜRrA M`>{UÁf¶Y éø¢7ÄC"0b &&fûöíÖÖÖsçÎ5XÐTÕv÷.öíC—.<Ë—cÅ Ìš…ñà ´kGûA*ÞâÅhÔ¨„iȢΟ™?¿ÇÓ§Âôty “Õ¿¿ÝÊ•hß¾£€Ö­[‡…… …jµZ“®i|}NLÍi—'))©~ýúV¯^]°S¥Rùúú:;;kŸØ²eK???Žã^zV4{Ø+g·CÖÙÉ!š´{š°ßþd:dïvÈ*¸ík“í?Aö›"힆ÓH­¨Öþ®4Ê’fkk àùóç¥?³ö„KÒÃkñï—BH´ŠõÍQMIÉoñ4QÙ7At¶Û3Ù¬ÔüUç¯prr2t¤TõpàéÛ—œ?O!Ÿ~J²q#!„DF’Œ ÆVsmÙB"’ÈÈ"G”ryƶmÄÛ›c€´j•÷óÏÃý1¾ÿþ{b±X[0²Þ²ÝY%¿ÉWkÅ´Lh;vlðàÁ 88¸mÛ¶ûÕjõ®]»¾ûî;í°WW×o¿ývøðá£f“®i.M—+³ˆ´Ï¢/ýþ«C0ê0Úꛂzmø¼R5Ø’¯cv‘=vÝÞ»u5’{\² zg>ø]jß³,5ªþŸåÅ_Ö´›'i=³¤Þˆ&Mš<~ü8""¢I“&¥?9§ÆùIyÉ74ýþ1±lUƒ VË!‘%!/zCn*Y•öåɲØòƒ­G÷º¿ï&xJøíÅ|ú=“*åËáë‹Ó§Ñ¬ºwǵk8{^^É@GëÍÁƒ5 „`ß>|üqáþÔÔ'K—2;w:°,"_oÒÄféR'CÏušœœloo¯½ÉÝÝ}Žæ¬:‹7*´Ž¤nÍ|_yc2`îܹ"‘hÕªU¯]ªTªÝ»w¯X±"!!@ëÖ­¿ùæ›áÇÇ×}-g•™2*íl_ÕoNù IDAT¼‚2+’=54¯`D‰ûbIÓOEº–q@™I®.ÊzFÝ}³±Caz2²ÇûËÆÌð Ó"³^Ñ®]»;wîܺu«]»vït‰ëßä?=£öúMZéӋ<ŽÜVézC‚læzC<%IÍ| ô‰eÑ«nÜ@r2¤R88ÀÚ'N ÊLõWmÁÛ V­ÒÍ Üùßÿx;w¶Ž…R ^$²ùö[Á¤IUç×ݧOŸ³gÏòùük×®=ÛLöœzÙ´Ú}–RIÉÄ[åææþòË/?ýôSFF7GŠïŠZ 1QÆ¢9ß¾‡ QoaÇjüë ^žÿÐW7†Âq ðý_ ס',þéš#6ç :SÆ/ _åGR5óuZñ–?===ƒ‚‚Þu¶Veg\Ÿ§È bs¦zÍdU™¢ž<™:ûË…²ÝŸÿ)ØuaMAk_[¿ÙÃHP¶YPo¦mˆ‰«+,,ðü9òóÑ¥ ú÷Çš5´®âÝEDÀÃéé˜>[¶d=ybvàÙµ‹ €ðùÌС‰63¦üSNé×þýû?ùä“9sæüôÓOÇúÉ2±OšÔmQ3¿Ô•k†pSSÓ%K–|ùå—;wî\½zuè“ 3À¬aûïºN»Í©rHò Mò MèZ…Q=ÆÊM`ãηrX¶âóªÕÄäÍ>?Ü£€¸Ójy2W°ÆGüeM~ i=£T+Ò¾®„ù³_§S.—¿ëUø"×ç¥Þb/NËk6V\rgJmVÏÂâÊéS<晴ÆÔÚ4AC ¦É V²¡J6TÉþ’ NBž6±ðZˆ*m©SªzÐvm89!5ƒapîî݃±1qqøþ{ŒIW)ädôë‡ôt „‰CÝݛ޺ÅÂr“ÐŽ[üü³eëÖUsHͰaÃ<==µÅBàÅZ_5’>Õ¥RéèÑ£ýõ×ÔÔÔ'D®zÑq×{¿È}Ê¥„èF~fEqOϨŸžQ|ÞÔÌ©jå%«ãÀ³÷<¿¨Àiñ§ªÝ<Ýà¢ÇTcÆyhK?´óg;ô/fþìוrFí7QfEI¾¡!ÓÄ5i²/=277?pà@ÇŽµ‹Ú [` Tˆe¹ó¢7$PÁƨ¹5·7W À†Ïtë†tóÅ4³ ^J¡­7ëßçÎAÛ |ä¶mCVzöDTbbУJ7Ü»öÉËÀxòDfeÅÝ¿_ÇÍÍ @´££óºuƃu•ñ‹\å‰DÇŽ‹Å„& u®¡cª0zH&½¼¼"##ßoÕjfXØH`áÂ…½{÷nÚ´©i#‘óP=çRBØ”PMV$gV »<šk“ ‘ûU­¿ðEÈO#ÏΫß%Ò¾JÞ•*—Dü©àúy©š Ê™LØ÷ôþKjÓAÀðA8ÐÎŽbi'­’Éd&¯ΙðO ßSÂ_`x¤M,l@>«áNÈ5'ä@iÌ0íÄ<71ßSÂïi$°¤½!@(„··n»W/,Z„nÝà×_ñóÏøúk¬[‡´4˜›£¬ó ×D,KFŽdBB8>ß$5©©06Vú´ÿ÷F6tp¥U°·.™ -o’––Ö§OŸÈÈÈŽ;ÿï?“&MÆ¥¥ùÊåcÆŒ¹víZÁôJ&ö<{žÓàêš~Ûz Ì\xÙQE:‰=®r&Š>¬",š~ZÆÔ8ê€J-#6¥dallŒr$êw¡ë‰š¾~Ò‚2Rª@vvvß¾}cbbÞ4 h)ⵉ¦Ô€ Ñ&A ö¶’Õ.HözoHKMß(hÑkÖè¶]\м9€éÓqáöíCïÞŒ®ªHOOòðø("S§Nnnn¶‹‹Ý°aâúõßcøûÃÊ ––¨W•2 Uù ¥ µ¬Æ&åzƒËÈÈðöö sss;{öl ‹+«€XúÃ?è+JÃcÐü³Âöm=f”ŸÊÚ_†ÕËp„ÿ®ÐrJis‘r¶Lh©óHìquÆC69˜}û£k33³´´4™LöøñãR>ÅVÀŒ0n¬' ±—f9šž³5^f!`,0ã1Ú®©© ×g²±¹åë²”ŠƒQ©Zoút>»³;3ï°»3ïÜsî9¿ÿn0jmßÎ; T~¾#ÃÔ»}›Z¼ヒ‘#Ñ»7Z·FýúX¹Òº‚ËŽÈ±š›‰ŠL(•Ê\½zµE‹pvvà2uªóûﯷ³ 3¿øâ‹¾}û¶k×Î|j­Iá¢Kßé  ÷:{cAqŸëü£ÝsW,–¤½&mçÒXP¿GYGkÌb&ÄNT×_í ùÄ»kÍpjñìÛ·¯~ýúÒ Ýî8 ¨^2a/™CpÇT 9¡c“‹DCìTëG]ÔCd´kMçK@€èhddÀÓâÄ 88`íZp¦OÇÀ8ÐÖf*T aaa§N‹Åã¦M;ãëÛÈÍ̓¢“ƒÜÜÇÿgg?~\uŠ™‹ì³š‰oj2/0êõö\gýæ¶¼¢¨ÕêþýûŸ?¾yóæG­]»6¿<èÝwñí·ÒÒÞ1âç-[Æ[±ó²­!”Q‡‹ã~3ðO/}«—Ô¢ xlNÏÒåÝdíêP¬… ÷¤%Öu ¸±Ú `òs ]ß¾};..î7ÞÀ3fâã?ÖëõsæÌ©W¯^¹„ïonÈ'§?ѵ%qiR“ù7&„ÄÅžÈv„Ôó£!h é#c,¡k¢!/3žžP¯îÝí[Épü8Ö¬Á‘# ƒZK—ZÝ\ÅñãÇ.\øÚk¯}ðÁ&L …>>>^í×ÏÚÒÌIA˜ã…nŸÀÙ_yœÚÄ9¼"ßJFÓ¿ÿ3gÎ4lØððáÃE¶'Põé`dff``àÍ›7,X`.­V§Ùxqá<¡ñp1]$F¡LdÃ"z®·ïó§½{[úð8êWìvÒÏ0ù·Y™å?¤´GbbbË–-'Nœ˜™™‰'ÍDNNί¿þºjÕª T\[aH9b:¿@_±Õ«1„&Mš´lÙ299ÙŒ›-6ÒK&S¸iäÖ*ã³t-RÔuk¢!5 ", üý1>Þ{…]»Ðµ+Þ|¦ô TRSS£¢¢¨ÕêãÇÿùçŸ&MšÕ­[7+‹«Ìæpz4)Ò¹¡M¸ËçˆØ¿TTS䛫×ë‡ íëë{ìØ1ooï§V‰oÛ€ÏÉ“6ˆD¢eË–8qÂ캭‚ƒ·À§wÁP%@ÓÑOX ÷¤…VÃo˜Ñ‘´“Åÿâùáfc%t©ù~~~ááá*•êÓO?Å“u&~ùåN÷úë¯7mÚ´bÇÒæcI“Qâ.?U0LS¡(ªuëÖþþþ)))•´ >ò…«äp];¥ŸSL=ûåµ¥á"šJgÉ-3'×Ð9U㚤 MÕÌÉ5ìÖ0EKsÖðòàãƒ/¿Ä»ï€V‹:u ªS|÷Z´@d¤uÕUœ{÷î5hÐ`äÈ‘ƒ¡ÿþëׯ?yò¤µEU.b3›‰Â ™(¾ÑW!-[¶pðàAþ©^¯ïׯ€ºuëÞ»w¯ØU“)ßɉܙ3Ÿ}ö???¥RÉ¿zïÞ½ÿýï ,0KgË“qÞÄw);!¤cÇŽƒNMMµ¶( ‘eŠð•_Ú…£\(Yþb¤Ï{þ¥Ä”f&nß¾ ÀÕÕÕd2BL&Ó!CxzzÞ¹s§´­~ðÈûï›L¦W^yÀÔ©SùWbbbšï,MäU„¯<娩”÷ÄÿcØÔH®I/æ¤ê#m„¯üümw÷ñÇèׯ_dd$€°°°5kÖèØ±cEÔ?‰ò»©‘|S#yî—½­èS(Š-[¶h4kj`¹ÃZÓ‚\}¯Tô¾¢h³S¯Dex†v¹Ü£gjœÅKˆ^Oöï'F#1IíÚ W®BHl,1•vf²7oÞLOO'„ôéÓÀ/¿üBa˜—뜓yÑá+ß÷F‰7*E[jܲq>^Î_}8†lj$ßÜFa õe 43±téRãÆ#„˜L¦aÆpss»víZéU>L€L‘ˆ°ìÍ›7ù̽{÷BòóóÈd²b{—WX‰ì¯ºò“þÙ—Ôiì¦Fò 媔²^òóóÝÜÜðG·nÝø®¡[·n5‹Ú‹‹u±ß鸚+Ò“„„„ˆŒŒ´¶L‰Ñ3Ëå†ð míDeQcá  y¨ž£T›älµýYÕP,F#ùóO2c!„ä剄xy«zà§ùæ›o(Šš;w.!äÌ™3[·n5^Æ¡P~Lú¿¾%š‰ü;Ì_ŠBÇpc­Þ¤}üsÖçqQS5¾òÄ=Fòhñ®>ªýošm¨ã)ÍLtêÔ À¿ÿþ˲ìøñãÔªUëòåËÏÝ(c2%Ó46m"„ð'¼¼¼rrr!ü¥±nýT{fž–wVY¢‹ð•ŸQ¾ßú?ü Q£Fx'áïïo^_Ï1äî÷rÝ*”ƲeËzõêuèÐ!k )>2%K¬*)’dªqˆ/—.‘–-É€„r÷. &«W[GINN΢E‹xqîÜ9GGÇyóæYGŠÍ Jf#|åÿ„(KyÏùÚB3qâÝ'.C¶¶Wìêcµìs)ÑL¤¦¦ {{{µZ=iÒ$ŽŽŽgÏž-ãvÃà @þ÷?B˲]»v0bÄBHûöíœZQ ¾³g¾Ü°A£T ‚ 68::nÙ²eëÖ­þþþÊž%Z%`´äø mÝPaëН«QP?»CYëg"‹.\ÀÑÑQ«Õ:::òöÎŒ¼-ql ðî^SÉê1·oß^¶lÙÝ»w­-ä9xÐÔ {á7I´·½ªÈÜ7šJgÉvµéý}»‡—DUï4íy†#:FW35¤úbosæ`×.¼ÿ>¬XÑ£±t)”¿ëpYaY¶}ûömÛ¶MJJjܸñ7ß|³gÏ=dSœÄbš#GtÌÂ|Cï4­S¢²ÝCÍ{9úM*S2SóqWC$¼þzAqѣà7СnÜ0ÛŽnß¾=}úôK—.Ñ4ݸqcWWWÞòÉ'Ý»w§¨šê®D Å ,X}i~¢ùÄLj»›¬@ASIÿÁ¢Š5•´ Å߉*•Ê£GRuèÐ!‰Dòã?FEE½õÖ[<àß_úvÁÍ›o‹‹;.—O˜0á›o¾Y´hÑÀ÷îÝ{ìØ1eï}P%PÜgso°¹7XÀP¸°h•Ó‚úÙMèz½û_¼xq·nÝ„BáŒ3Ì øh1äwÙÃãµÒZTÿ5mÀ0dȽ^ß³gOk ©8þ"¿H0ÎQ ƒ%õìi=­gb l¬5˜]/š • ùždm$´MTÀ©Á|LŠ©S@¥ÂÅ‹ÐhP·.,X€Ѿ}E¶Éqœ\.wuu]»víªU« úuë~øággçêQò¸29Pl1ª!+ù/TM%-EH1.iëÖ­#FŒpvvV*•õë×/,èïï?jÔ¨Q£F5oÞü¹›Î;v̵G#ÎÎÔ«w#.@hhèõë× €öíÛŸ?Þ¬ÇbÃDPçßf_]"küfÅ¿ƒ–H$[·n5£´¢˜ÔdÏkj™‡ û*;I­—ÝLTc´„\2p§õL´Ž=£góŠTÄrPí%tˆ”•Ñ!ÒKYÝÐéƒÎqî:u‚‡RR@ÓP(àêZÖœ9sfÔ¨Q­[·Þµk×Ý»w¿ýöÛ™3g¶jÕª2…Wþí¦R=à†wtlPšc¿ó—ñÜg:þ±[K:,ÒaW/•Ä…êÿƒEdVâÍÄÈ‘#ùI<Ç5jTÇŽË7l€[·R6lØœ•õõ×_+ š¦íììT*•»»{VVÖ‹@• ý4shŒFæA½qÊ©ôª—¥s÷î]•Jl>iO£Iãdºl"sÙ¯$±±±ëÖ­ëÙ³'ߥZ·Œ\¬¡`Ðâ¦ñqÔCH!HLó#ÝdBwúeÿ>T'²²ðûï°³Ãûï#2ááx÷],[VÚ*§OŸŽŠŠš?~vvvýúõ5jS3QvvTçÝdÃv;¸µ(-mŽÑ‘íT|SIÁs¤±Kô´ól» (6Ìa0öíÛÀÁÁaÈ!#GŽìÝ»·PX‘ÁùãîîÝnÝJûþûO®_Ÿ4iÒ_|±víZ•J ;;[©T:99½àT øúÙÍÇ=§~ösáç…V*öu®þl¸±ÚÐo«}ysE«—.]ZµjUzzz56ð É ¢!é,‰y ¹ø(ò³üEÞX„H…âšV§UÌ›WðøÎPê×€¿þÂ;˜>½ ëN'•Jõzý Aƒòóó |ñâÅ-ZÔ¤D” QÙ*j?·©¤mRÌ`ËéÓ§»víºyóæÌÌÌM›6õïß¿bN€Ë;ïºFcíÚµW¬XqíÚµAƒñ¯Þ¿¿Âº«y·ØÔŒÐ޲ñˆWQŒ ÂHVLÕï&ôb„……-^¼¸:5«{.^Eæ†äù:žò¶_â& ³ÖP &î•ij¶¾EŠºèÜRóÉj¨Ìš…‡ÁOûþ{,Z„Ç 9_ýMݺu:$“É>úè£O?ý”oSܲeË'Q^D`Ò<ÿSzSIÛ¤ø0‡¹ „ eK*.{÷bÀ€ÂåÇŽ›={ö¬Y³ÂÃÃ+oï6BôǺû;ŒÍ'JÚ^eÆ9Ù—™:¯ ÔK=QÌ›‰º]„…N"i¯éâWzûº”G°0å°I›IêõvùÉÎî÷*ÝìÜiÝ€çÙ³¬FSt9EQ|]íêÍíMFŽï‘C=[÷•Ï"¿Çf_fïï2š±mnUdß¾}ÿüóµUØu…T¸ƒè§ÚÒ§¢!.OFC¼’TƒÒµKå†h=kx©¿D¶N~~þ¤I“Ú¶mK6lX§N¦NÏ=êÚºuЖ-X³³g€FÎÚr«&"ûrt!¯Ó^è@h6öqå ß"ÏŽ4gBËé’!Ç»ü$KÚkzxÌTI‚ËE¥W< 2$ÁÉÉ_©4îßOVÙ»³)Œ*—0 |»"…ª¬ŽWˆ°Ó72ï.B[®”RÙ´oßþÏ?ÿìß¿¿µ…Ø.*TJ‡JéÙ.ODCNéØ$†Û£eöhÀ`GQm$‚` *¥{È„n5Ñ@¯×oÙ²eäÈ‘NNNQQQ)))—.] >sæ ÿ†  K|ü1BB`Å ,]Šï¿ÇĉÖÓ]5)cf!ƒö?ThGI\(õ{‹B¨Ú„O¯t3AQ”ÿܹ˜;W¼s'^23Á×ÏöìTîúÙ¶Cãábg™›ëÝ~µØzB±ù£G V«lzž·-PR4ä´ž½l`OëÙÓúb¢!âª7nW=8p`TT”H$=zôüQ¿~}__ßgßÖ¨¾û®àñ… ÈÏG½z°~=¼½Ñ§jr1ËBA¦Yz)gf¿aÓС (ÝÖ­Ü“‘ŽêMaýìÀ·ªä°D!„ÅÙOu)GLwþ4<ÿÝÕ‘7n8ÐÚBª…јzör?ÇÃuíÔ’ô’ í¨£!F›81VgΟ?߯_¿åË—=zô«¯¾ÊGœ;wî\¬“xŠ;pù2zõ‚Fƒ>B¿~¸zXöyk¾ô„9ªéeÐDMš\—HZêõ7–-kñÒ̲{ñúÙ6E£ë »ûMÍÆUmWTa|||âããsrrôz}M‰ž ã( zÉ„½dB ÁSA4䄎M. ±P­Å‚P©0DJ‡Èhך N3‘}ãÆîÝ»gee¾Ñ¸q‹»w-³Gk‘w‹Ý=@-²§†v;WÃsœ>—d^`ô¹¦v4oÞ\&“ý÷ßõù5XœÇ—É:­g/;‹¢ÑÎRÚOôRGC¾ýöÛ9sæÌš5kéÒ¥'Nœ¸ÿþ¨Q£,œëò idd A°,î݃Ÿrsñ”* u*·#Teï%vÆÑÚZÌåî±Ú|ó Žm‘’¥Õº¿×ÍuFßWK'aR“Ýaj}×w³ƒG»—(‡àâÅ‹5SC­‹¿Hà/*hH¦äÈ­{Üìô¦Ñ¸V ^4*òóNÛHè—ÁYäçç¯_¿^«ÕΟ?¿sçΉ„ã8]»víÚµ«åõð# žžØ·çÎÁÏññ ĈظÑòrlñ ‡9lËL@—.8uJ±r¥óôé–Û©eѤsÿvQ‚¡'¼«çyìê/†¬¦óvR×jè–J!33óرc#FŒ°¶ž h4䘎É) qPA-ºÈhçj ILLôóó‹oÚ´©T*MIIquuÍÍ͵µúÂü·ßÆ„ X½ׯãÞ=  Aõ>Þ××÷óÏ?õÕWûöík³Í<33A<=1j6oÆâʼn Í| IDAT{ ¿<ü dtdtœ“ÐÎF?¦ cÑŸ“ݸq,’‚êÒâKõ€KÚgÊ‹+˜ÞPP?›B‹iÕ'ïòY(;ŒPÇ.Ñ[[Ž… izذaƒÖT÷ÚkqFn|–®y²šzßĹ'©®YX£4¶HQ¿Ÿ£P™ú¤iÝUk•Fëª}>²Æ]Wß!Ý×1ÒÓn¶‹$DJ ‹Ì ñ} ®›¤ž©ûIaŒ5°ÖO…/3÷îÝ›={öµkןŸŸ««ëíÛ·|ùå—ýúõ³Y' Nxz@§NhÚãÆÀرøüs(•Ö•f9Dö`R[[G%`Ù0`ìÜY 0a‚%÷[IÜÝl<;O×d¤¸Ó×277\\¬÷zUØç/{kK«t²/±GkZN—½[ÓËÉ Û-M“æëèESÐ'Mû¡‹x€ì”#DskIšˆS²õ›TF…Ÿ“Äv/a1\{ ‰Ò1¹E¢!Žªƒ„‘Ò¡2:D*”ÙÞáp'—Ë]]]gÍšµlÙ²‰'®_¿>33ÓÙÙ¹êR»sÍ›ÃΉ‰pwG~>Ì:_ÕÙÙ]¥Lâutö¯ÚcÏbéjñرˆŽÎ^¹Ò½Z˜ ZJ`tEëgWͶ^åŽ-ýÆIG™;E8ò‰ÔÍöNÀ•Àùóç8ðÑGUïdÌ`‰À}çEÓ @,è!¸ndõƒíEMDþ"Ê@ àˆÇ wí:§g7¨L16ár9"¡¨Bª‹T8ÃYl®ZU" Á:XB¿ç < 9¢cŽèäCH!HLóe²ºÉhˆ†œ;wnäÈ‘AAA»víš6mZnnîÌ™3Ô©SÇÚÒ^ˆ&Mpð ’’àîŽsçУ>ø‹[[Ve—š`ÊÖ…¼BÇq6^4ÏÒf"©mÛz€KLŒ1=]ìåeá½›¡X$í1i38׿´w·—#‰¹S†|rò=­6“ ø×ž¯ïV½™={ö‰'_¼€ -ã  Üi*™áúމk+ám3NéXo!5Ⱦàž`"n4UÛý?÷h™õ*ãHÑG.âz´@MÈ!-ó‹Âø›Ê¸Á]6ÆÑüó‹Î É`ÉÅGÆ"ÆÀÆØXCAìÒŠsC®^½ºgÏžO?ý´Q£FEétº† ®_¿Þ‚**ŠBïÞOž„áQó¾’f` µtU"¼™0ªÊa&!“&MúðÃ[¶lYiºÌ€¥/{¾íÚ]pqi/—«¶lð…÷nvLÜXcÐ|’aqù{½§ Ù¸êS³Xh ´™ÄÏ©rµšÚ´q6 cÇŽmÓ¦M@@€µ…¼(·Œ\Ë5 œõ¶ï(-æƒó¢é á€Ýæc—‚¯ñI=ûº}AدeF;˜­ªCˆ”Þä!+|:ÀNè  ç¦fë{Ù =+³e¹'M ²²-!— Üi=­cÏèÙt–lW›¶«MœTûʆèõz±Xl4»wŸ?`À€6mÚœ;w®E‹6~oú"|ò ÂÂÀµ|ðŽÅ–->ÜÚ²ÌMF&>ÿü󈈈ظ™°Â^ûï¿à¸oŸåwmv F&ôêg{ ü‹Jrô-ÍõU†Ø%z]võœR\ˆÐŽê¾Æ.,Ò¡VSšµ¹T<ó3yòäü±˜‰9yúÒ«¢»ÓT>GÖ(‹Œ œÔ1½ew ©Læ×2[P¯£äé{›"ZBöisí幨QT¨”ží"Ùíe—íçx£¾ÃFÙ'q€X äȳ0ßÐ;M딨l÷Pó^Ž~»Ú”ÍšígþÓO?ùøø>|X*•~ôÑG~ø!?É3((¨; ž€¸¹ÁdBóæðñÁ€0u*öï·¶2óÁw!7–9sÉ’%_}õ€¸¸¸Je¬:” ¹£GMZaïf…¿7at$î7€æãÅù·ØÿúªS3Þ‚þÛíeîÕäßÉW`ç)H?ÍìQf^°ÜIßZ8p`̘1—/_¶¶Š­g#5Ïù¤\Ô¿Sˆ”v{4$p×Äe²¤½„pÇÄ}•oØí)3KŒÀ¼Zâ/\Ÿö%õ„Oe¬3ßBŠÏ I+27DÄØŸÆá™:$UÃdõ¸,ÝZ¥1®ÈdÔ2B9pà@TTN—}àÀŸ~úé÷ßïããS Gf»ˆDøùgÜ¿8€µk1iôz® ͺ)‚öe s,Y²dîܹüã7nT¢,s`辋Ë{ûP…âÆâÅ­V­²‚óAËÀ¨ 9WY±#%vÂþp5k€g'a·•v’ZÕßIò0ŠÑå{[ŒuÚW󔑽{÷þõ×_~~~mÚ´±¶–rsPË,WOêJtJÕ ¦áuië ©wœ¥­Äï†OêØZj«Ú$¤oâŽÕµ÷–ø ÿ_Ž~¥âùCU=eÂ#uíØ7§Ñôè”[§2ceÇ«H4DÃ‘ËÆ‚hÈi=›`âLÜ*gõÊ£hH¨T(-Y;ß/ãï¿ÿ3fLÇŽÏž=;uêÔž={¾òÊ+–;*›„… Å÷ßÃÑR)þý â»ïЧµÅ½CËæX·nݼyó(Š’H$z½þÖ­[•¯î…°Îyß4d""Wå{;þ<¡Ë!|g?Õh1MÒöc)U͇$Ÿ&x®Ô¥‰ Ñ0³åˆÜºuë¿ÿþ›3g޹6h.FŽéíí]E0 ,¡c ¬ö‘˜à(ò žý¶.¯ýô„ÃSzf˜ƒè—2}Ä¯Û ë•l5 ñ-u®Ä}SÁ­h€Øæ~Nö*TJ‡JéÙ.`Û¼±Ð³Ñz6ÑôxnˆˆB+1Íçov— rärùG}tþüùk×® :´C‡ƒfY¶V­Z5N¢|øaÁãuëpínÞDŸ>HM…—W•, Y02ñ<3ñÛo¿M:@³fÍnݺ%îÞ½k0$Û*hé:(•¨SF#RRP·®˜ m·½“Š–€c)ŠÆ+ŸJ›O|þçÕ½{w[®0S1‡ë¿‹ ÷^èKŸ™™ùꫯ6hЀû­Á¼´HQÇ ®Ó%%`>KãdõlÉ[N–kð65[¿Vil%¦/×·¯BŽ4†ðÆ"ÖÀ^0°¦"§X?Îèu`ç¨7ßìâ( kÖ(%%åìÙ³:t°žØ*ƒ^õë1q"$´jB‰† ­-«œÜŠ0^X¨k6NÜa¡¬¤÷lÞ¼yìØ±,Ë~ýõןþ9€úõë'&&^¿~½E‹[>¬ô urÊlÝw뫯¬#ÀLð9¬„!2ªßV‡²8‰-[¶ôìÙ³wïÞiii•¯Ñ¢äßb¯,×_[¡W%W<¼©ÑhÂÂÂbcc9› “þûï¿]»vÝø2õ,JgI¼‰k%±ÄCGpFÏNÉÖ¯U½…Ô6OYrê ©pÑOµ¥ÑÞöy¾Ž§¼í—¸IÂì„.*q°33§üoÓæVi:Õ¢Ÿºž¸t¼iëh=k¨æ‰Úf@*ÅôéÉ”• :||À²Ø½»*åR𠘦’‹èFFFŽ?žeÙ/¾ø¢Aƒ ÃtîܹU«V°ùL«ýHÏ5h€þçk 0 i9³˜¤;ú3ÂFò;<‚Ët‡'œœœŽ=úÊ+¯9r¤²EZ×@ú•ù²žì}*øÕ2 ƒ Љ‰ T*m3R˜——wòäÉÿþûÏÚB,D6KæäêìÕ0yåÎ/,‡´Œc‚2$UsTÇÌv‘\­çд*·wP’ë—.¾5ºÿΈ?Ç/ÆŒªز»—»¯PÒãx]ÿ9¹†Î©×DUhjÁÜ\óÍ ©–øûãÞ=8‘[¶àµ×0dˆµ5•™‚œ‰‡îÛ·/<<Üd2Í™3gÁ‚üæµ×^ „Í› +‘g‹ E‘¬¥áEP(3gÎ …õij%I@@@xxø‚ ¶mÛ£ÓéJZ=99¹{÷î(Šš2eŠF£±¤x  ËåÎÎ×2úr¯8eÊ"‘ÈÕÕÀÆ+AÝ‹’••µsçΪû©&«¯àÿÕ1•±‹l†»gdŸû/ÕÄ=µb´ŽA¼â/•±2TY¹\~îÜ9BI $„0Ìã¿vª‰Û¦2ÎÌÖ§¨>þŸÿÕØLí…ᆵÚT¶l!>>$"‚B¶n%üAXÛþƒ¥ž2EøÊŽV?ûÇq!!!&OžÌqœÁ`prr˜˜øÇ6l˜å—«™ B6Œì²eÖÔP~8Žûûï¿ëׯ_hÈ<;»bz„ÚÛÛ3fñâÅ;vì¸uë–Ñh,ºåË—‹ÅbW®\±âA™#Ô¾ò‹‹K´SÅ2þ|þïFQßq`úô镤ðÅá8N­.æ¤`ûXÀLÌÈÖáÉ d±ÿz¦>mÈîYÄ+¢´¦ÊPe1ìììÜÝÝu:Ã0ßÿ}fff)ïW²Üa­iA®¾WªÆî¾²èŸÈ3Q–¦Y’¯?¥c O[¯ˆÁ@† ÄLJäß­-¨T².1¾ò=¯«Š}577wÁ‚¼ã³÷|–C¼"F_)ª*›?ÿü³wïÞyyy„ààà¾}û¦¤¤”w#&ŽÜ0°k†±™ZŸ$UQcaŸ  y¨ž£T›rÙjr®0 &ùí7Ò¿?aY¢×“!CÈáÃÖÖTùwÙ_ùΞÊç¾sÆŒ>ûì3BˆN§£iZ(êõåìµf5ß~Kš&£G??\ÊÛnÜPÀÄÇ›SÆ‹±fÍ'N|jybbbXXo|}}### !üì_²rå³›ÊÈÈˆŠŠZµjÕ»ï¾Û«W¯zõê=ë-(Šòññ©ûhJËðáÃóóó-qœ–"ã¼)ïÖó/ »víâ üýöÛo“&M°dÉ@ ‹mó÷sþüy:t°¶Š`3ñ"ŒÍÔ¦1UéJ™œœœ••Eéׯ€~ø¢ÕjͲñ’¢!t¼" Y5%K·Qi¬‰†å×_ @Z¶´Å‡&ð•oëø3Áqœ··7€ .ðK5jäààpïÞ½Ê×XAÌg&nÜ A™˜6B¶n-ÝLB2ºw'YºÔl2^Œøøx{{{{÷î-\¨R©fÏž-“É888,Y²¤0X>nÜ8;rdY¶o4ïß¿¹dÉ’±cÇÆGÜÝÝù>>>QQQ•rx'õ„icCùŽ.Jƒ¢´kÃÙ³gù¿Ã¼yó!|É¿ëׯ7oÞÀÅ‹-¥·°,{îÜ9ÖOWe ’ÌDÃù?PeV)ðâüðÃ4Mó_Ý'Nüþûï¥$K½ Š"ÑÙý'F^5ÑG(•dáB²g!„,_N^ܼimM0(¹_ù_ŠÒ߯Ç5êÕ«W8VmããÖæ3\à$²m!„Èådǎ笵s'4¶ â8ŽOŠ;vlá’7ò‘¢¨±cÇ>|ø°è*|å¢mÀš®Àcccç͛פI“ ¡PاOŸ7VÑ«ÔS°&²?\}}•ž”ü+ÈÌÌäÿÂÇgYöÎ;|0ˆã¸1cÆX½zµ%—µZ}ÿþ}k«(7­SÔ…¡ãZ³™‰_ä†Iª<áe1ܲ|ƒçL¨Õê_ýuÑ¢E„sçΉD¢iü”1q$FÏ,—Â3´î‰Ê’¢!ù/q4„eIãÆ ‘‘„b c¾K"üä~r®Ôü‚ XþKõ"˜ÏLôìùØL;VÆ•YY Š"€öêU³)©(k×®àéé™››K9sæLa)ºŽ;ž?þÙU `E =6¶,{Q«ÕÛ¶m;v,ß¿‡ÇÃÃcÊ”)‘‘‘æµ!„p É8WâåaÉ’%}úôá³Sù̉ѣGB~ùå—bCN6©S§$Içέ-¤Ü M×^xfçD‘^ܽÎÊÑ-Ì{јTç‡jÄ+¨xÅe›L›HJJ"„ܾ}›¢(;;;>(™mm]侑ݨ,ˆ†P%DCŒÕá¥\äå‘+!D¡ µk“‘#‰ÕO±("|åÆR]wëÖ­ìÛ·Ïbª^󙉶m›‰S§Ê¾Þwwd¾÷žÙ”Tˆðóp"##ÓÓÓÇŽ˧Ozzznܸ±¤ñ¥nݺØH²}ûs÷Â0LÑi “'OÞ½{wå‹ÚCŽVol(O;]¢Ÿ(LŒ:t(€õë×BΜ9 U«VZNÔjµL&ëСCÑI:U‚ãZ¦èõÆ7I垨ü]ñ¢G1ɹn²·ØØìP–eûöíKÓ4ï'>ûì³íÛ· kë*†¢Ñé3Ñð ír¹!FϼTÎbï^"Þùk4$7×jJ¶¶WDøÊ5é%þù8::ÚfºXI˜¯7SÁv‘]ýááÇŽ™MI…˜6mšR©6lXllìÈ‘#5T*={ö¬Y³ø,ŠbÑét\;vD\œ>*Jú¼~ 4MwèÐÁÃÃ#,,,<<œ/ERí¡hxvæßfK©ÎלgY–¯ŸÝ§O­[·‰D)))F£‘ŸCkSØÛÛgff:::Z[H¹é*£ÿó´["7\1pˆe¢>v%×âŒÜ·rÃ={ËÇÀ}×1Us¤®] 1ý»Òø‹ÂØK&l-¡ÿV™b ì7n’)NÍ$'±× wäúÊUòI®¡„~ÍÞru»K!--mÕªUÆ rwwwpp¸råJƒ -Zdmi%â$ zÉ„½dB ÁU#­gOëÙc:&%ÛÕ¦íj$„J…!Rº‹ŒvT·êþE0·oC£€eËðãX±£G[A‰ØÒeSÉ]È÷ìÙ oß¾¶Ü‰£Ì`H/& >–(üçí]¦ÕF®V-h¬—gÀÙÙÙ××—ÿ³„‡‡—%o¶eË–öÍŸO€ëööeÙ—JUü ãê Ç]GѤ³LÉ÷rü‰¦M›.IHH°ñô‘øøøÝ»w[[…™9®e¯à‡XBz¦jöjLücé}Å„Lí#Ky;K'¹¯ÐWÇ <Çqü Ï>øÀäÉ“ !U´²H!|4dJ–. YUR4$ÉdÓ¿¸gäHèhB¹pXx`qÏkª_yö•£x½zõ°iÓ&KªzqÌQ§¶V-Œ:u/7Ÿ~Š÷Þ+Óê"Ñ~±@â·ßšALùÉÊÊúøã(Ф¤¤ÆGFFþñÇNNN÷îÝ‹‰‰9räS¸‹V«P¯h¦ÕšŠçîÎÁÁÁ¼ú«”R7*+†Ý3H}q‘®pyæyæèdÍõ•þ)_\¼gÏž…oðóóØpsÀäääF;Öd2Y[‹9 –ð¨i§ zÈ„®Y=Á`{Q‘€¿ˆ2(*¹À¶å‰ àçj͘1c̘1'NP§NRÆ)«þ"Á8GÑwi\}‡t_ÇHO»Ù.’)-¤pÓÈ­UÇgé|¨ë&©†gê~Rc lÕi|QVþþ7o"$ééèÑ(ÙÛl4-¡¢v~~þ‰'„BáÀ-§É˜#ÌñÎ;°g23 –¼ý6BC˾Ž+|Ï3ƒ˜ò3cÆŒœœ¡P(‹œœ”JåðáÃõz}Ñ÷¤§§{zz>».o&Ü4`›7ߺ…«WÑ¥‹…tWABD™Àq&DÀèð0Š1iÐr†ÀÑ£Gñ¤™°q|||Ú·oïëë+—Ë '÷V”;M%3@ß1qm%´”€S:Ö[H ²/8o$˜ˆMÕ~áІpíÚµÈÈÈÏ>ûÌÇÇ'))I§ÓiµÚ† òÅŒ«uhj½p½˜®=ІD= qP$tˆ”•Ñ!R¾¹a•§ysÈÈ@½zhÚÎÎÈÉÁÝ»xõÕJß5o&ŒªâÍÄL&S·nÝø~UóåL¼ø›7Û§¤àÆ X¶Åê?ÿüóÏ?ÿ`†aÞ‰DÎÎÎÎÎÎ......%Lð92™LÜ­nÝÊ۳ǵÆL”LíÖtß¿íÝÛ)¬´n-iyq,á ÓkOŸ>MÓt=¬­´ð¡™ê‡-HgìÖ0»dEœÔ³¯ÛôÝbýZf´CUnÃ`YV Æ®]»Êåò~ýúµk×îܹs-Z´à ©½ ˆ(Kè` ýž3$˜8ÞXDë™[F9¢c!… 1"¥ƒ%tw]_Xµ?ü6mpíärX´?ÿŒÅ‹1o^åîTdŒ¦x3 àµ×^«\•€M˜ ˆDÊ^½œ¶n½ÿõ× ÿþÛ’{V©TkÖ¬©U«–ó“ÛkãYxóaggwI*m ÜÿãW+kª 턃‹ u©Ç™‘R7ÊÎS ÍàTÉܹ»Ñƒ¡}ûö...Ö–Yø¤Ñ‹/Ϋì“eq§©|ެQ':>N„<©cV»ËøÇ©Læ×ªR9bÏð믿.Y²dݺu½{÷ž1cFnnníÚµY[š5ñ ø€€ –\|d,b l¬5°üÛ¼h*T& ‘Ò¡Rº„®ŠÎB$?¤èí 77¼þ:üý7ºv…·wåìÑ‘`,.Óh4îß¿À뼎*…m˜ ÊÝ}0`iáýò¡ÐŠÁ0ŒÑh¤iZ"‘Ô~ýuüøc³¼<‚R&-Ô™XU2—Í4è/r ¤µ\îuöhôQ|òQ‚¯f–™™Þ¸qckË1.ê_iK™Û£(Æ]—É’öÀ÷U¾a·§¬ŠÆ8N:%BBB EJJÊÿý×»wﯾúÊÚºlÏ"Ñ-!— Üi=­cÏèÙ¢Ñ'Õ¾*GC>ù3gB*ER&N„D‚„Ô®mþña¦¸œ‰'N(ŠÀÀ@ó︒±3Ñaölåºuž ._F›6Ö–S& c|ºv%žžŽ¸sÍšY[š-Âèˆ"žskIÓtûÕN•ÌÕí,à(H9м›ì³Ù—U@0eʽ^_Åæq=zBêgi+ñãqþ“:¶–€Úª6 )Ä›¸cuí½…UíŠؼyó¨Q£:vìxöìÙ·ß~»C‡U+²fEì(*TJ‡JéÙ.`ÛF.ÖP0hq³¸hH¨”î&ºWÇ)•€Pˆ!Càà€Úµ‘’‚Ó§ñæ›æ¼CÙSLÅ…9øGU–Ì25”'(¨bE«3}:Èœ9f“T9©ÌÈÈàááÁ?å†%@æ7ßXOšMss½>ÂW~h¬º°¦:•Ý=Hue¹.ÂW¾}X’@ ÉdÕ»~W•f\¦öí¬ªúé(ŠéÓ§·k׎eYFðå—_šL6]´»j‘Æp‘jÓì}ÈCµøÉJYþTc3µk††*SÜ›a!dÔ(Ï?7ç–om4DøÊÏκ'Çq|[¢sçΙs%••Õ¦M›°°0smвA®ãÇÑ®öì)öÅÌ®]ä¬\ b£3Í!Ÿ|ò‰··÷ÇQ$a‚õ·ìì÷€˜ ¬)цረ´SÌšýÃÔ£˜øm¦Üëìƒý&Ñ1Ç9Ž •òwUM›6 2DaÉf猞åcU“É´sçNƒÁ`oo¿oß¾ØØØ .ØÙÙÅÅÅÍŸ?_(´•¡Ùj€M ².q“D{Ûçù:žò¶_â& ³ÖP &î•ij¶¾EŠºV¢ªwšö‹<ã·Ñ3=ð©·½{ÃÏ|0|åJÄÇ›aË"0=3›ãÊ•+ÉÉÉ^^^…m*•¯¾úêòåË%Í-¨–2 ˜2«W#6¶¤·p!!©@m•J{ò¤…T•Š¢óóóþùg0¯¼’%“Qª*Xôúë¨Swî˜G§9àkoÿüóÏJ¥€Ýúõëoß¾ФV-I–-•QEˆÐøM±ø£“‹Œÿ‘/ ¤„ƒzÔ¨QfŒáY˜Ÿþ988øÂ… Öò2’œœ\¿~ý°°0ƒÁпÿ¥K—ú~~(ÿ5U(¨]@þš5`0 %4 [štÛ¿ÿ   ÔÔÔC‡‹Åóçϰxñb§¾}4ÌȰ²ÄªÀƒ†>èµ°Ä´{¾õê½Cw022røðá,ËZ[]EHJJºtéÒžò‹k¨ "## ŸŸïãããçç×´iÓôôt@ðÉ'Ÿð‰ñ5TŠFC<ކKh=!§õÑÚOFC¬"5<W® ÂÕó 0Ÿ4%Å8¼N:nnnC‡MMM-ºnvvöرc=<<*x ÅbÆQŽçSR˜Ãd"ëÖñ¡Û·€xy†!·o€4h`Q‘e`Æ êׯ U«VBCC !$;›P‘Ɉ¡äΘ/iii ,(vÈN.—Ïœ9S$pvv^¾|¹Ñh¼º{÷·ß~ËwQš6mšå¿8·nÝÚ·oŸF£±¶êOZZZff&!„oUÿý÷ßBjþòÕ%ËÖšäê{¥jìî? ñ, 1ØX4¤$Œj.ÂWþg€¢pI~~¾H$ …999O½Y¥R%$$¼õÖ[jÕªUô%¾€„„­V›”” {÷î»víêÛ·ï¦M›Ö­[çåå ((¨²C~¶a&&L ™2¥ U¢aChöï'ûö€ôèaQ‘eÀh4òN€H$¢(ŠÖB ~~È޻׺ ­ÎàÁƒ¼óÎ;E2 ³|ùr7774MÏœ9³ðÇsåÊ•½›6mùé'~”ïsóÎì¶ &“©¦TF¥ò믿ŠÅâÙ³gBNœ8±bÅŠüü|k‹ªÁB˜8rÃÀ®QÆfj}’TE…}‚2ä¡zvŽ>RmʳåzÙè/ð“s.î[¶lÐ¥K—’ÖÈ|ÔD399¹èò‘#G(<‹>@xxø¼yó¸Gy‡›6mâ×=yòd¥Î#lÃLœ>Mœœ@FŒ &Óž-p³{wòóÏ S§ZTdÙX¼x1ï$ <¸pùÑ paäH+j³:7nä}tjjjáÂS§NµmÛ–ÿZwîÜ966¶è*¦M›E‘#vîÜÉÏþço7«¿üò‹››ÛÊ•+­-¤º¡V«W­ZµpáBBȹsçD"Ñ”)S¬-ªë“jâ¶©Œ3³uÁ)jAcAÇ+’US²t•ÆûFÖÚ2Ÿæ¯Š_¹AQp½ç=Á²eËJYÅÏÏÀ‘#GŠ.ܲeK»ví ŸÖ«W@¯^½ !äòåËüYwãÆf=ˆ§± 3A‰‰!®® ÇïüôShÈ»ï€|û­EE–ÜÜ\B¡ðöíÛ…Ë£'L @N÷îVÔf]>|èìì à·ß~ã—$%%…‡‡S Aƒ‘‘‘Ŭvó&±·7Îq\DDEQE­_¿Þ¢Ò_˜uëÖ˜4i’µ…T’’’!wîÜ¡(J&“åææB²³³­­«›CQ$"{²§W‘hˆÑÆ,¶uTFøÊÕ©,!Ä`0ð'ÌøøøRV0`€§N‰&LX·nÿ˜ŸàÔ“³)O>ªÛ´sçNsÇXÊLœ=KæÌ!o¼AÒ«™5‹ìßÿô{bcy?Á¾ñ×°!HÇŽ ;vXHd9™9sæ³#ùäæMºu­$Êú 4@ß¾}9ŽÓét ,àKqÈd² ”Øæ¸c‡ïر#//²dÉ~àgÏž=Uÿbäçç߸qÃÚ*ª Çõïߟ¦é„„BÈûï¿ÿÇ^úl¤Ê‚‰#1zf¹Üž¡uO|"Í¡H4$ßJѽ”¾òü; !„ïIPú*|¢%?8Ç“œœÜºuk£ÑÈ?å3ù5jôÔŠü81€[·n™õ žÆ²#Ï%6–¸¹€kÖŒ&GG+W¬-«x’’’\]]Ÿ¾Iâ8ƒƒ4qqVÒeM6oÞ ÀÑÑ1))iãÆ|f ßW3%%¥ôucccOýþ{Ö™3üÓO>ù„· φúòòò,3»bäääïÔP.233—.]Ê{²Ñ£GÛÙÙí°ÕÛ‰ª ÷lĪ_y„¯üýòb£! Œ†ì¬Šð•gÅ2äÑMéܹsK_eÑ¢EÞzë­Â%cÆŒ):1~üxóæÍ{jE~H“&MÌ'¿xlÌLBΜáó'LCQ J¥µ5•H±)-Ñ..ˆ{æC­ödddðÉ•óæÍëÖ­o‡ƒ‚‚Ž?^–Õ¹,ÈÃåŸrÜÛo¿ÍÏø¸téRáÛþ÷¿ÿ …Âÿþû¯RŽá…ùý÷ßiš~z¼ª†2ÀZ}øá‡&OžLINNæGªj¨á93GË›‰Ó_é £!Òg¢!áÚårCŒž©TgqhŒ:ÂWžzÒÄq\ƒ œ={¶ôUÖ®] `РAüÓÝ»wúé§EßPìv4««+€Õ«W›÷žÅöúÜtê„'H¯^ÂÜ\‚:uàèhmM%Ò¹sçgJºwÇÎÞÉÉ–×c]fΜ™››ëååµdÉŽã<<<¾ûî»1cÆ”±Ô<Õ©¼½µb1ßì„¢¨U«VÉåòíÛ·÷ë×ïÔ©SMš4àîîÎ0Ìž={,Vw¶\ ‚êÝñËì\¾|yòäÉ>>>»víš6mZ||ü˜1cðhöu 5¼8Nþg!÷F‚Æ2a/™CpÕÈFëÙÓzö˜ŽIgÉvµi»ÚÀA@u”Ð!R:XBw‘Ñ΂Šô ¿jdí)ª‘èé`aEík×®=xðÀËË«}ûö¥oÊÝÝ@~~>€ŒŒŒ7òÃÀ<‰‰‰—‚Oê´)‚‚‚rssmØÛwîÜ9pàÀ{ï½W¯^½›7ofeei4šÆó|j¨ÁŒ87¤Ÿz@H!XBKè÷œ ÁÄñÆ"ZÏÜ2rGtÌ€šŠ¡Raˆ”î*£Ëtw”Î’°t–#Û=e=dO\jy3aTþ«öÜ;®ZµjÈÏÏ7 S§N]±bEÑž·ÇŽЭ[·¢ÛIKK[²d‰‹‹ËŽ;,Ñ ·²‡>*ŒæÄ ½Ý¥-¬-¤Ü †¦YŠâärkk±ùùùÞÞÞ¥ÓË>gìðòÑ£×/–?™¬Ñh^}õU-Z´ÈËËã8®nݺ®Øj2 !äòåË'Nœ°¶ …eYŽã ‹‰‰!„DGG×$WÖPy(Y>Ì¡Ï+SÒeÃEªM³sô!Õ’ ECô›©å33–ä?‘ãu~6ÂW~s½>88ÀîRúU=âêÕ«<==‡~ôèѧ^;v,€ï¾û®p‰Ñh qqq9ó( ­²±É‘ Û¦MO†y%.®NZñ¨*ˆœœ®ÒtË&ïØá3i’µåX‚?ü°°\«s ¸¸¸°,[ºo}æ æÏÇÌ™ -\hggÙ¥K—7n 0àÈ‘#}ûöݰaþ}û‚‚‚*÷À*Äþýû о}{¾Éo EY½zõ7ß|óûï¿÷îÝ{úôéYYY|L—/ÞWC ed£ßÓ‘Dï®Â^öüãMäQQþžëìëõ:Ö„9R’ZeάCSƒì…ƒì…€ÄDpíQ4$êÉhˆ£€ê ¡C¤t¨Œ‘ eE¶-¡°ÑC(ÌË5ÌÉ5\3pëQ É [±·ô¹'OžlÎÄbñÇRØÞKô YlÚºu«µµuYYÙBZFµƒðïÞùl€I"6<ÞÀû÷)Ïž@tt4‹Å:tè««k¯^½ÂÃÃÏž=«­­}ùòe"§#&&†l½†Çã…‡‡%šßvK\]]BcÇŽupp2dˆD"ÑÕÕ3fŒbÂFAÛqX ÿL4F‹yo›ˆ–Þ“ð+‘ýlƇ?Ù~Q±‰ª´@]¥8SÕr+õkÆ*ßj+ gR™«!_³J¸Êx}”¨vtJ‰÷xÍ{AÇ ¦¬ŽF£Uþš„F£},íÞ½{ð‘ÔÂÎDÖ¿Ò)))d ij=zaS,nP¬š·‡¤$óT"#`ñâÅ………VVV7nôññ111!rF@fÿ08ޝ¯ï† „B!ÙZ:Ç#""„B!“ɼpáÂÓ§OãããUTT233÷ìÙÓ©“® º:V³oþ¢p dŸ5nʹ ¢©`¶Óè©G›‚W¡íÔQºg¢Zo£‘f®vÊ€¹LƒÑ“A)• +\q®פ`\í €TÝÝ݉0ä¶nnnípm@ÖÍÄÖ­[ãâ∬r„’’’hà@PNJ"[‹œ¼¼ø~~EvvÄÙÙÙ¡¡¡&LÀ0,==]"‘P©T¸yó&ŽãŸŒçÍ›÷Í7ßt731mÚ´I“&]ºt‰J¥;v,))iè;±´ ´/Ž •_¿_~ AA°s'|ûí§wäóùDáYƒ(®UQQ‘––Ö«W/²å´3%%%... ¥¸¸˜N§oß¾}Á‚¶¶¶dëRÐíðÑ%÷zçͬÿ&å¤@Á°ý*6Sþ0QþX’¸KÐçke3ÏΘZÊ5§Q†3©Ã•iö@y+~uU\t[Œ $ Ôu¡r^Д4±!WÎ]9zô(ÑCœB¡xzz.[¶lÊ”)Ä Ÿ¼ f‚ÏçWVV]Lä‹JggƒÔTtéæçG¶y¿}›sõj¥»»ý¬Ydki¿ÿþ»––ÖäÉ“»Lu툈ˆÃ‡‡„„èêêöë×J¥^¸pÁFkÞ+èJ$î¤ÿñ&8 £Có¬Aýg•£¾O;,5 ‚kb¢€Uç¨ÂÅP#Î •=”J¤ æKëhtúˆ?”í=õ¯Mj¨N•Ž8¤b9–Žãø;wNŸ>}ùòe>Ÿÿ»\ºti§Uj#r°ÌÁd2---KKKŸ={F¶––a0u*`µu 7`üxÐ×*”•Áß¿ÄÉ2#GÞ÷òJWR’÷èÅ/¿ürΜ9]ÀI°Ùl¢ÃPPPPttôÉ“' &&&!!Aá$ŽÃ|öÏšÂá³é ê;ñJš˜ÛNfŸ¯•;G ¡,^·Žwa`ݽU¼’;\Œ4ð.о)éËfihX8뀭/òBÅ@¡P¼½½OŸ>]ZZzôèQ—òòòƒ:99 0àØ±c\.·sô·90pëÖ- ‹Õ«W“-¤e$2ðêìÙ6²w/ŒQQP[ ³f‰ ¼zÕ>úd …2(+kô‘#ÔŒ ²µ´•­[·:;;³Ùl²…´ž?þøÃÄÄdïÞ½ðÍ7ßìÞ½{Ñ¢EÐö”6Ý„ššš_Í”báófE£À{å%šÖ)7ºÊDÉÓüËCêoÎáæ…‹Ed0€:h«²åþ¬E·z&TÜàÙsMÂÀq—Õ™zØL¢SP+æW½¡©­½lÙ²çÏŸ'&&.[¶LMM-))iùòå&&&Ë—/'²@eù0îîî:::b±˜l--@:hÀ¼²x¼V‘ž›6½y½t)œ9í%O–1ÎÉQ‰¡ÅÆ’-¤­ÄÇǧ¦¦Þ¸qƒl!-ƒÏçŸ:ujß¾}àää$ ‰Â^^^7n$ºi(PЪ««=<<ˆ©ûŽÃqáa2œ¦fÞ©÷µºüù¯‚+>õÑþÜÌ`¯×°¦ôPö} >ö’Z¡ñÝq3=Î{Ì“~®¦¡ªfúFž’6f:‚ޤð*Bôßaû÷ïôèÑÊÊÊ‹/z{{×ÕÕ;vlذa½zõÚ½{wóã4;r p6±XL¶„#llº¿•ClØ€Þü»x!„ØlÚŽ"eQllÑ®])7n-¤­ÄÅÅÝ¿_Žþz«ªªB¹¹¹ EEE…Åb!„ ÈÖ¥@^9rälݺµ£ô÷¸ú`+vñíר¹ÒOlm¼J<õ°àŠO]cIï ƒ8‰üÚlIã>.\`0°Í'$Øš¼ÿÞ …7DÁVì¿Ç5]ö;333 ÀÀÀ€¸q+))ùûûÇÄÄàx³š vrc&BIIIû÷ï'[E Y±ø¡•÷òzk&îÞmOa²D"  ‰Ddkix<žD"iz?RÁqœ õêBhݺu§OŸV´WÐFˆÊŒ #--Díe&Dõxö9a”_ý)›7â|_Î“í¼Š1þï†3G¥R© ŒðÍ&ÇËŸ¼¿BH*Fõã[±«3šu} …ÿý·¿¿?QµÌÍÍdÁîË™hhhPUUÅ0,??Ÿl--àÖüù ÛÁ¡•Ÿï×ï­™xð ]¥É:µ+WŠ{ôff’-¤­¬Y³FEEåÞ½{d ù0{öìIMMEÍ›7OEEåÒ¥Kd‹RÐEHIIiœïÓ§‰Stm4bž*¼µ¨!Äþ‡8Ó“ó`-·è–Hò!¿½mÛ6 ÃhúÑ¡©Q~õ¼ªÎíÊžþôþ¤Å§))) ´¶¶&~·DüæÅ‹I|ú’˜ PUU]¶lÙ† ˆY#yAØ¿?¿z­KÁ•HÚYü U]M{ù’òàÙBÚ •JåñxI²WXXÆÞ·o߯<;wî,..öSd2ËòäuîÜ9PVV¦ÓéÏŸ??|ø0ÙŠZ’BñmqÜ:Þ%×ú¸õü’;$3OÚÐÿ1ý«ýEÅÜ‹Ný÷ !´fÍš;v`öûÎ?µDœ<\ÂýèõŸÈéÈá-¹Ø›ššäææÆÄÄÌ;WIIéÖ­[Ó§O·°°X³fMjjj+O¸-åbº \.WjhˆPVVË>¹s'²µ};-ÑøÏÔ´c”Êü»w3öïrëÙBÚJQQQaa!Ù*þEZZÚ!C&Mš„ÊÍÍ;vlDDÙ¢´„={Þ\¨T4{6²¶Fýû“­é}Äb±¡¡!q£!¤UTTrssIÓ²™ U$ˆnæïËyaÍŽò«Ï>'Ô|*FA,Ï›7”””Â.]Eqˤ•ÉM,a\ý©hæPSSC$”6ÞÙ‰øÍ†††VÙRäÌLDGGÏš5K¾V:дi€èPË>uèúî;Dâß¼yè»ïО=£Ræ‰Daaaááá²mÐÊÊÊjkkÉÕPXXxðàA„PEE…²²²®®n]]¹’´†´4D¡¼¹,¬XB.¼5Ç¿Ù4a‰B‘‘‘ààà ¤¤ÄŒ×È‘#;9f°2Y’´›÷ n°ûÆì†Ä]ü’ØÞ¶Ù¹ÒÄ@þå!oÃ*ÿ_ŸqBÐPúŸx‡ÿÀçó'Ož jjjQ‡žžïÃ)ŠiÖ¢CêQA°;v%·gõˆ„ÒÆÚ6Ë–-{м%òçÏŸ·åÐrf&>ÿüsøé§ŸÈÒ.»»#€ìáÃ[óa—n3âMŸŽëé¡ÒR²…´•Í›7S(¢{Eç#•Jq‰Dúúú””„ºÿ>Ç#E‚¶òé$¯¥KßlÚ°D¡éÓ§À®]»¬¬¬àñãÇDRqpp0¹ÂþK}‘ôÙ~þ»©¡ÃëžíÿWjƧ©««9r$èêê>yòäáf^°ûɶf}ŸåÒS¶ì{¶Ý>6‹Çã ¥ÃzöìHäj}M›6Q©ÔðððVTnb&–/_þ믿5säÑ€ ›•E¶ùƒY_±X¨í%DÉÆÑÑ‘Éd’’~úôi{{û7nÐéô+VÌ›7OUU† Æd2;_‚vàÝZÀúúšš0mÚ›wìíß¼ppè\Yÿ¢ººúÊ•+T*uÞ¼y¦¦¦  ÷ìÙëÖ­«¨¨ Q[#‚”yRíß6¢þÅ!;WÖÅ0Æ^RzW½Ï×ÊZ=šÕ-ŒÅbyyyݽ{×ÔÔôÞ½{ƒ rû‰9x7sà÷ÍúŠ©RL†Ò¤Bxu­} )1™L"q4##ƒH(ÍÈÈØ´i“™™ÙôéÓoݺ…þÃG§Ó¥RéŒ3nÞ¼ÙÊ£¶Ú†(h& ÕÕHYaª®nñ‡»÷ÌDýãÇqgÎ4sŽN– 3˜˜˜HüÞ`áÂ…yt˧“¼""ÞlŠ‹#CÜ‚‚‚ÀÇÇý3EqîÜ9ǽ¼¼`Ö¬Y$jsñÜPáÙ §lßÌCœíÅyˆÎå« IDAT°–û:NŒ·|Mµ¸¸¸gÏž`gg—ŸŸÿ`-71ÿß,ÐO“ÿ·(ØŠ9µé‚­ 1¡”F{Ó—ÄÌÌì¿ ¥DiuuõäääVEþÌDdd¤««k`` ÙBZ>d†…µø“ÝÛL‚ÐÐÐè¿þ’Â,­F*•&$$dµ4·U„……€««+B¨ºº:**J*máµM,ãìü©ËÂË—o6±Xdˆ{ƒ»»;œ:u !´víZØ»w/B(##ƒ¡xñâE'K’ŠQÑ-QìJnˆÃ›°ÊÓŸ±cWr‹n‰$üV^a^¾|I,â8;;—••±R%§lÙg9u-ûÆIèœ3'ØŠÍÎíÀ¯ê§J% ×¢¯¯ÿòåË–.fâï¿ÿ€Áƒ“-¤œ37Gù­0ãÝÛL ÷部ÔÖLêÈDo‹¥K—vÐø ßÿ½§§'Žã\.×ÂÂ⫯¾ê%¿¼¥9I^b1¢Ó‘žy*QVV¨©©ÙD]ö¯¿þšØzàÀ«W¯vž½Ž?XË=ßç‡8eþ1»!7TØÆ…çÏŸé*ƒ®©©!Þ,‰D·æ{÷p/ØŠ´§e'ZT*%J:ŒŒ¾úê«””¡Pèíí ¶¶¶ååå-VþÌ„@ ¸xñ¢|ÅŽœ2TõîýæçÄD4cF³ªbws3òð@ªªâØX²u´•/^ØØØ´{ì0Žã±±±B¡P"‘XZZQ«k¤À(xŸf&yõê…<<ÈQˆBH"‘DFF?ž?üýý;Y+Eòd;ï’ûÛ°Ê(¿úŒnY;<ýÇÅÅiiiÀèÑ£ØyÒ[ x•­w' ’`+öE·ºV,µ´Ž&”8p€xgÀ€õõ-Xv‘?3A€ãxK}™TU! CL&"Šï܉вeM°Û› VJJäÕ«>$[ˆŒBLK†„„ „®\¹ÒâK4¼]î߿ߙÓÉuï§f„¨{¶ŸÏÎi·„èèhÂ!%çoÎi¶b?ú¾MO¹ážuÁVì×qZ'ÇñÛ·oþùçÊÊoº´ëèè>ÉÓÓ³ùÁ^r–ÍA‘‘aaa1zôh²…|.>ÿîÜÐÓ“ÚØŸaØññC‡¶õ Bß¾0~#ªGÈQKR탼ÍLðù| à FGDR¿í¼Õ˜šÑ›ópó:oµ”~³ˆö]°qãFât’÷ñÛ«i}‰ô” ûŒ#GÔÐI!ç»víúꫯfΜéááѳgO]]Ýÿš„o¿ý¶9CÑÚÓát #11ÑÆÆ¦±"‡,òÕWðè\¸£FÁÓ§‚~ý .N99’“Ãkk°´lë!¶mƒR}`æLøá¸yììÚ:¬L¡¬ŒõèÊÊ„YYÊýú‘­¦MŒ1b„ žžž¡–þé–––.¤¨¨hìØ±[¶l™?>†at:½ƒÔ*PÐ^(++ëèèTWWWUU56Ñn#¸ŠbÄy¡¢²x‰T@cb–ch–ãé&CéT¥¶ŽŸžž>bĈ¥K—îÚµ«ñÍíÛ·ÿðÃeñ’”ß…T%¡ï} ¦A[ïGj¦ÃA´òÇ’Â(±gt¡:pàÀ{5?(о¾¾‘‘‘¡¡¡žž^mm­¶¶ö§‡’K3¶¶¶çæÍ›þ2ÙÞÃàäIÈÍ…¤$˜5kÞ¡Cà쬕–÷ïxx4=Bz:p8o|úÌÌÀÒïC£F½Ý*tÅ2D¯CBgfšŠÅ®d+i#ÊÊÊĤBó¹qãÆÉ“'9bjjjnn%%%vvv?þøcÇhT  C055­®®.--m£™@R(‰FŠ‹oKDu0*˜yÒ¬ÆÓÍ}è õv{¼‰¥%„…§'%((‹Bé €âã1>¼‰Ò‚®åb1ìß[¶€™YÛäÊ"jBáØyó@EæÏ»¬#Ÿ”–––——÷éÓ',,ŒJ¥jhh 8PMMíÝ}NŸ>½zõêU«VíÚµkÆ nnn¾¾¾ðÁåL ä‚Å`>ÙÎÏ:-zuUäû@¦ò‡{N>ž{ITpMÜP‚ïhÚRìüVéj¦•@]YYéââÒ¯_?@0sæÌ«W¯ª««_¹rÅÓÓÁ½/y•‰R©õ]ߦ Ë÷ ©`–£iyáâü+b—¯Ú¼ZÓ‰Èñ¥ùèÑ£4¹¸µ GŽÀ¢EÆã¹9ØÚ¶ç!¾ú ÜÜàûïÛsLÙAWúô«ªòóò4ûÈ!ÏŸ?ÏÏÏoL¸J¥µµµ111îîîzzzáááEEEëׯÿì³ÏêëësssÀÓÓóÍÅK‚ 6Àöí0aÙR>b&žlãgÑT°‘GUßs¼ B]$%‘-å-ÿ5 ? ²N‹¨Ê˜ç1ƒoü°å_D‰«’¥PÖÁ¬'Ñ­ÆÓõûѰN)ePUUuíÚ5:>nÜ8//¯„„SSÓ7nôêÕ‹Ø!ç¢Èd(Íp m\˜Ú§‡jFî4UJC1^™$1 7÷h¹úAöíÛwøða>Ÿ¿sçN²µ4Å¡CÒôtêãÇÍXãh& 0o̘3f´Ï€²Šž––Qa¡~Q W;‘ššú±M8Žã8¾fÍ{{{"g]á$´mm8r^¾„ È–ò–÷ÌÄó_'„T%ð<¦b<„&á¡Âëâ‚HqYœD*øg¶ßÖ—aäFÃ:|&â_½*¼¼¼¦M›–™™iggwóæM¢Ÿ‹ÅzÉÉýAOY›z[®Ö!ól¦ÒSƒ„¹—Å 3ÑI|þùç\.—hC'ë0¬£G…..ø°aíà°««aÔ(˜845áúõ7o€œçO~M>ðºu ­ _}­‹4&›†††Ol­¬¬Ü¿§‰Q Ç4™äÕT )¼k&R _R0"HU*B÷VñJîJ$|˜yÒl}æž4ª29SüÄGJJJUU•³³óõë×ËÊÊÎ;wíÚµ„„„Á†ý0:Òp­ƒœ#õ° R4 Ä ¨CC%ÞãÞ*^A”¸ÿ&åÞËå à„Ü/sP©Ôï¿ÿ$‰ì—pvv^¹r¥ÅyÈŽŽ’1cêìì ¢BÇÐl5-†F£9òÁƒ"Ñ¿Zjii o¯ì :¡0ûÌÖÕ«ýxŽãJJJzzzööö$ŠT  eÀýûå‘‘¼˜«º:ŠTúv“Š §W¯$eeÓI“zÌžÝÛÛ;++ëÆq?S§N}þü¹ŠŠÊñãÇ]Å{}þùçñññ†mܸqçÎÄúBjjjŸ>} FNNŽy͆wWð*žJFQ1r#mýRzutƒ’æÿDƒÚmD[O1yyy6662†Éb±NŸ>íîîîîîN¶yC,æ/_^ig§ºl™žž€¿?ØÛÃæÍ JZÐŽãÅÅÅIÿ”.¦R©ÖÖÖ:::T*5;;»¦¦†xÓÝݽ͗(è@ÉãÇ´'Oꢢ$Ožè…[Ö³g½‹Ë]‘ÈÚÏÏÉßþ‰* ,--sss‰µ;wî̘1ƒÅbYYY…‡‡÷éÓçÇ”H$?ýôÓ?þˆã¸‡‡ÇÙ³g‰rÓ§O¿téÒÊ•+ƒ‚‚:òœ?…Tqëyeñ’ñWÔÔ-ÉL{ŒßP“!yDÅb´Lçˆv31qâÄk×®=~üØÕÕ•l- :ŠŒŒŒ¬¬¬Ï>ûÌÉÉ ÁÊ tu¡ª HuµµµwïÞ%^«««ûøø¯…Báõë×¥R)0™ÌÑ£GSä³|§‚®É«Wü›7™Â;w¨éé´wî Ó?^ìì|W,î1{¶ÕG¢”† òðáÃýû÷ýõ×°{÷î-[¶H$OOÏ .¼qüMqûöí¹sç–••ééé?>##ÃÙÙ™B¡dggu¬;> 1õ0@P_Œ«[üÍ8!LøQ`îC÷<ÖŠ:Œ®si³±±ÑÕÕ}wÂYf¹xñ¢‘Ь iÂÃaëVâ¥iuõÈ >»zàáC77rÄ'PRR2ü'ñ„Ïç———“«GAW 2øüV~V Àï߯ €‰q##°±a®X*¥¥QÊÄ0É¢E(8øöüâbˆˆ ïÜ9jÏž9‰‡>|øPWWwéÒ¥|>Μ9›6m’H$7nÜh¦“//¯çÏŸ;–ÅbMœ8qÍš5vvv³fÍ‹Å?ÿüs+Ï´ ÔfKÃGÖ?ûŸ! ÝI€Íd…¥wÅ‚™~ò'ÿ7Õ^ìØ±£¬¬Ìßߟl!MSYYyëÖ-EÌD³(-…Ï?‡„?ÿM×¾xQ94 >`ÈRõ5¦¦fãëêêj•({¤R€‰añâÔÁ|õJtüx©Ÿ ={àÚ5JE›B¹A§×­] 11éññõõ´?ÿÄæÏ÷úê+£fԙݻw/|ñÅÕÕÕC‡={ö,“É>¡œœœÞ&&=%%`³A‰ä/ØÇb& ¸¸8!!xm`` p ZCBL›%%`aW®@ß¾ïïŸqqì۷ű±z¥¥Ø»Éºº/TTâ†oÞì4gÇß-k5+W®<|ø°››[bb¢D"1bÄÅ‹‰Êµµµ•••öööÍjþüù¹¹¹NNNNNN½{÷611Y»vmdd$†a†Q©Ô¬¬,›¶kn’¸u¼šLÜ󘊚¹lLJü.†‹®uÂZ4)ZMÛA†\λt™ ˜2eÊÕ«WmmmÉÒ4»ví:~üøo¿ý6~üx²µÈ[·BNœ= 'ÚìÜi{ú4ÃÄ‚HwŸæ]³®ˆ¾TÐN‚+@ 77 cc€7Óßpý:–œ¬ZWZ€0 ú÷O`0nÕÖÝ´iØüù.Qíà#ªªª‚ƒƒ1 {üø1Ì;wÙ²e.\xúôé“'OrrrÜÜÜ!MÍàÑ£G999ïîojjêä䔕•¥¥¥UUUÕ9“ÂZT™,åW"!©™wôÑZ…VèÙ!¢¼0ñ€of¢ãqssËÌÌ$[E³àp8¯^½zòä‰ÂL4 ƒãÇ!?=Rݹ22ÀÂÞoÇ,{¼Û[\I¶}™C"U«àØ1€E‹àË/!&’’x11ÊÙÙ5h`2Õ¼¼Ò´´Â++‡¬Zå9iÒ@€¦+((ˆÏçkkk×ÕÕYZZ^¼x1$$¤q«ººº¦¦&B¨™YúwîÜÉÈÈHMMÍÌÌ$þKT‰€ªª*8sæÌæÍ›{ôèÑA§R(ic㯨ÕdHe³Ö¤/#;D”.ꠌɢÀ®µÌµµµaaa°xñb²µ|ŠW¯^±ÙìÞ½{Óé2:,[°Xàê ùùüþýÅ ÙÙÜÇèc|b™#555''‡xíââ"Óf d‚ÚZ˜5 nÜ*¾~­ôNª(SW7™6í•¡áÙüü Ž7®stñx}êæåeâím °¥s¥8q‚ÅbYXX4º‡~ýú©¶_Õ8 쬬¬¬¬gmq/((¨ªªÒÓÓ눫e^¨HX‹Šb$2n&l§1’÷òBE 3ÑôíÛ÷óÏ?÷ôô”J¥²l&`þüùaaañññÎÎÎdk‘úõƒÓ§Áßpzö]]²} ‹U[[K¼¶´´TQ‘éš3 ÈE,ÓéôÒÒÒõÓ§ïMJ2§%èêJÝÝŸ«©Íž &èl™:•,...ÅÅÅYèšB¡ØØØœ8qâúõë'NœPSSkßñû(«Qìüd}’Øv*ýÙÿÅ·Ä"bhÊÜ#hW‹Ã0ììÙ³‹/f0dÚc€X,ær¹iiid ‘7¦Mƒ;d´Â—ËöìYrrrcL™¾¾¾Â2*ø/D‘=.—ëææfll,•Jõôô®&'ÛH$ Áo¿ ÕÖ†êjêµk£þúËyâD°µ…Å‹!$JJHÑ|ø0::Z–ãç ÕÔÔteûÙZfaùû™™ÙlÛ¦¥¥E¶–ÅL())©««×ÕÕ‰Åb¦¡¡aaaaeeELÏ–””¤¦¦2™L]]ݲ²2>Ÿoll} Û¶móóó»|ù2 :´wïÞÄÿå#GŽäåå3´´´Ë[͇¸˜;::J$’qãÆ¹¸¸<þ¼_¿~—.]jéPÉ{„¯ïK’~t€ÌÇÖ—yabÔôcK§Ò5ÍlÙ²ÅÐÐðÞ½{d ùááá555Šžé­#>>þÚµkõõõd QÐ}yùòå®]».^¼¡¡¡Ë–-#Ê7y{{;–(½eË–ÔÔT???PÔ•i5„™pss£Ñh¡¡¡—.]Z¶lY}}ýŒ3Ö¬YÓ¢ç ×”íç2Üw1›ÞUö0HS·¤p_ãå%dkù]ÖL@]]݃ÈVñ)´µVÄ# IDATµÅbqzz:ÙBä:N¡PÈ•ãø»†F"‘ÔÕÕ5g±Cœ’ŸŸ¿eË¢Prròwß} #GŽôõõ%VWýüü¢¢¢¡ ] ¾S:::Ó§O‹Å¿ÿþûÑ£Gÿýw:~ðàÁ‰'6çK÷ò¼¨8FLWÅÜ~`*iËç´6SèÚó²×gpOYsNYsn/nn{Â.k&¾üòËÜÜÜmÛ¶‘-äSÔÖÖjii¹¹¹I$²å1å—‰'’ºøìÙ³ÄÄÄÆù|þ­[·âââH”¤ Ý)((X°`QW·¢¢bçÎþù'xxx¬Y³fÕªU0hР˗/Ïœ9“d­]bf‚J¥nÙ²…B¡;v¬¬¬lÕªUOž<±³³›0aB“¹{µÙÒÇßóï®à±säÛëÛù1ƒÂëb1·£VH5mÞü25m›Ú³9ŒŒŒ ¼¼\$Y}dmmm33355µÊÊJ²åÈJJJ!‡Ó.][Mÿþýû÷ïßÌ+++9ŽX,.,,´°°xùò%B¨¼¼ÜÐÐP]]½Cu*h),ë‹/¾¨¨¨¸ÿ>“É}ú$%%ihh49‚¶=µ€²¸i}&ßOÑjfôŠIÑuqUíÔxk&šý»B]—'NP©Ô¥K—’-äSˆD"²%È1ÑÑÑ¡¡¡\.—l! ä6› …FFFb±X,ÅËËËB'Nœxøð!Q_Aç³cÇغu+BèÙ³g†©ªªVVVþwO> —þõŽƒ'ïãK„£´3xù—0ØŠ}}VC_|[lŶbW$4÷^¾ Ú§8p Fd:d—N§¿zõŠˆWÐR455ÕÕÕù|>ÙBÈ%EEEÄ ãðáÃuttJJJ FEEEyyyZZF»|ùr^^ž¡¡!,\¸ÐÝÝ]Æ‹ôwaˆb-£OŸ>ãÆãr¹ü? Î;s ®½ )xÀOù]ødk×¹PX§Ó˜XùcICq‡,Ù´bf¢Ë.s@ïÞ½Y,V»ro_’““û÷ïߣGììl²µÈ®®®²\äT¬!‘H’““íììtttFŽ?xð`555eeåììl33³3gΘšš뤣G&[²‚7öïß¿±’÷÷ßyðàÁõë׿W¹®2Q"†õÛ+ƒË%nî¼Z©Sw$t5Ìb-ÿª8ÿªØù˦Ïë”5ç½wL=hÞÁoÚ³¶ã ª(xý©jæIS7§Ph@WÇš¦ÚÅ/Äjjj)))¡¡¡d ù(ÎÎÎ&&&=zô‰d®‰ìC¡PAYYÙBÈ.|>ÿÞ½{¯^½€™3gºººFFF€ƒƒƒ¶¶öëׯàÏ?ÿd³Ù^^^пÂI()¾øâ‹ÄÄD"\]]½½½ëêê~ÿý÷wwãW¡úBœ®Ši;P 0ZÌÎÁµ¨ã¯¨©™v©û-‘{Y͈œ|C®úÖ øVyÄá·EÒf$hXŒ¦€Çï*DKRŒ 6T­-˜‡ëR¿Üÿ’••åââ²|ùr¬nD@£ÑJKK#""d¿3™ ‚Љ‰yô葌/f)èdÊÊÊΜ9óèÑ#1bÄÙ³gÀÕÕµW¯^ÄlÖž={X,‘½ill¬¨!wlÙ²öïßÿnnvU²ôúP1*T§I¬åEMkà•ËwúÆ1BS5¦Ôâ•ÉM×fÔêA}·-juª”Æ|ë-XÕ3‰VªÕx:üóöäjcþjAgù.n&¼½½ýüüd¹´Ç»{÷nc§(ÍÃ0###"\Žl- H¦´´ôرcáááð×_Í;÷ĉàáá1pà@b²á›o¾IKK›={6¨««+ÖÈäáÇ×ÔÔ9r¤ñͪd)ô£€¦ ÅÌ“þÙt†ŠQüQÀz2Qp¢Y³Ú ”Ba´˜WñÖ`•Þ“ð+‘ýì6=ÐvÁ®¡rGDDĤI“FŒ¡ð ´ˆ¢¢¢MMÍ/¿ü2,,Ì×××ËËëÖ­[/^¼Ø²eË„ –/_N¶FÈÍ›7Gmhh˜ŸŸO47¹>[‘ yT•B3OÂá@¡„‡ "Ŷ¾ ì_ÑÐЗ—çââBÚ ´ N.~ŧž¡Žù?Qw¦ácÜ^Ä-¹û¦¦‘ó—J}×+¯ï.罎“L¢Þ–>ì]Я½B(::zéÒ¥2”àææÖ¢Z Þ!ÄápŠ‹‹É¢ “(//_¿~=ÑšÅbmÙ²…é:tèœ9sæÎ ... 'Ñå5jÔàÁƒ+**Ž?¸X©RÀ àoÑíÅÜ´cBŒž¼GpyH}üF~qÌ¿¦0÷íÛ×§OŸääd’ΠMhÚQôœ©¢zT|«Ye¾ Õ|y^$ðY¨ø¶Øf ½-Nºƒ™À0lóæÍÇŠŠ"[ˇÑ××OLLÜ·oÙBä„PlllBB‚ÌšEm§®®î‹/¾ r+ Æþýûƒƒƒ…B¡³³óÊ•+‰Ú!!!óçÏ'[¬‚NeÓ¦M°wï^¡PX“.• –Å|4i€©[R¬å…«O=,²‘¡+MY÷_÷Kuuõ[·n 4hÁ‚D—Wù‚ÃlæJ‡ÉPš¦Ý››¾ Dˆ /L„¤`?§­A{Ýb™ãÔ©S,köìÙ2¤]PPpçÎ;;»áÇ“­EþHHH P(={öd2å²s‚÷‹Åt:]*•úúú>~ü¸  €Á`èêê²Ùìââb33³   ^½z :”FëÊÉí šÉ€’’’Ž92”² q—ÀÎaäNÍøST“!ª2Öc&Ýa¾’†Õž‚‚‚~þùg‡C¡P|}}wîÜùÙgŸuúI´!]r­Ã%à¯ÞœÐì³¢Ç[ÞÔÛÐu¢Nø[íŠw½’6ör[k(t 3!û=ztÅŠ³gÏ>sæ ÙZ( òòrƒáïï•––fmmÝ·oßçÏŸÇÅÅ 2$,,ÌÌ̬_¿~ ¡à=._¾ìïïoaañ縥×1 p1] ûl&Ãq£É¤Ðêêê½{÷þöÛo<N§Ïœ9sÇŽÖÖÖ¡¾ÍÄ~Á+¼.î¿Y¹÷²¦ NHøè’{½ˆóæ¾ß“rR `Ø~¢yX[è.fâÊ•+¿ýöÛºuëÆO¶–––öý÷ßO™2E1IÛ ¤Riyy9Ç“£ç ŸŸ¯£££¥¥åççzûömOOÏ)S¦DDD„††N™2%))ISSÓÎÎŽl¥ d©TÚ«W¯ììl+UUܨ LËBIßNòóTVV~wæ’Éd*++7þ¨ªªÊ`0jkkïܹ“””„㸪ªêêիׯ_¯§§×¹gÓbŠo‰ï,åi}F™|³Yý}w Òÿ¯1 041ÿÇÔV9â¿á×dHU 1©0 \Ö( h^µ‰Ž(ë-ƒüôÓO0þ|²…(h$IxxxXX˜X,&[‹‚O!  BDõ¡ãÇ#„Ö®]Ëd2ÿüóO„P~~~MM ÉBÈ R‰DX]:ëë놵[Kñƪ?wîÜ!û,›—  8ÁVlVJ³úhÔ—HOÙ²‰ÖÁVìÄŸùïnò­ÇÿæÙ/ü3Žœºis†í.†sçε±±™4iÙB>ÊÓ§O#""ÆŒ3dȲµÈT*ÕÆÆ†h"J¶ïSWW¯««;hРï¾ûnß¾}Û¶mÛ¾}{ïÞ½ŒŒˆjc;vìØ³g±~!/sË HDÂçÓ˜Ìê“'ÕÖ­«÷ôÔ õ1b^h( Ã"¢¢ˆ?$‘HÄår?"ÞmâÃãñ„Baã\.W$ÕÔÔ$$äË/¿œ3gNHHÈàÁƒmllTUU`ÕªU_ý5±¿¢ýº‚&‘4e庻w©ó狵ž|üøñÆ #ʨL:uêÔ©ÄþŠòÕ š!„a˜  @0aͦ•”(;:ÒKK…|>‹Õ†&'«÷í /23 oß¾-=Ä“'O¶lÙrëÖ-PQQY½zõºuë Úý\:^Tmjm–´4Vl1ªéo–á šNOjM†Ôaî§b6kÒ¥Ú¿ìÅ'èFfÂÊʪ°°Édâ8.ƒetÝÝÝÝÝÝÉV!¯`–™™‰a˜£££¢It§Q[[{øðáêêêÿýï,ë믿¶°°X³fÍàÁƒÇŽKôÍêÝ»÷ýû÷ÉVª@n .ÕŒ§úâ…RQ‘’¹9¥¨ˆÎã‰^½bX[ ”ûô ”þqÏž=ƒ–›‰9sæœ;w!¤¤¤´xñ 9šxÛiôÄ]Ò¼Ðf™ ˜ÙÄ =.Œ?EΫ•›[Œ¼ùQ]€„„©´Y±$¤¶hÑ¢ôôt²…È%YYY%%%²üÿ·kÀårW®\9räH„‡Ã¡R© ƒÇãá8þÅ_I$ÍŠS à¿”.YRgaÁËÎFÕÙÚ"€ºˆ„76g³?ñAÂFŸßÔ |˜×»w³ú÷¯ŽFUŽjöîEÕß¼)ÊÈh΀Á`Ðh4.—Û¢CWUU•——·B³lrkaC°;#XØÆqp Šà=û¥e_j™›íïPjjj FŒñnX¯ì0gΜß~ûm„ d ‘Kø|~JJJJJ ÙBäGta]°`žž^vv6†a)))/_¾|üø1>|øöíÛ&&&àëëûnʾMR~áÂë1cªŽZJŠnR’äï¿@yûvÑÍ›ÚkÖ€šÝѱ9£¥¥¥‰D"{{{¢×WóÑÓÓ#œq× E¥µ?†„‡bWñL†Òú¬mÙ—ºÅL€ŽŽNÏž=B%%%2XàÈÛÛÛÛÛ›lò †a¹¹¹4ÍÉÉ k¿ŒónBmm-•JÕÐÐX±bʼn'®\¹2nÜ8W]]ýäÉ{{û_~ùESS“H“k ¢T  ùT?zÄ;z”îèh@KMÕ»q£†J…%KTW­âzxèNž *#G¶bäÖLt=̽é M¬:UZ›-Õ¶oM蘰ÅÌãšyÑèêXé½7ÍÔu1ÝÞMÖ½Ìܹs‡ÈL“MvîÜyïÞ½³gÏêëë“­EÎPVVvqqÑÔÔ$[ˆ|€ÊÌÌTQQ±²²Ú¸qãÿþ÷¿   +Vhii!„ˆŽG;vì ´±±EÆrw§®44Zü¡ü|Ö‘# :ÝlçN,3ÓüÔ)޳3¨Ï™Ã¥Ñ´|}@ÅÝÚ{®0T%°OyN”&5f‚“'­N“V§IÞá0ó¤yýÙŒ›fWä‘’’’   –®®u>>>N¶]±XüôéÓgÏž!„¶oß¡ßÿ]EEå§Ÿ~B±X¬††’…*)Äb´`rtDÍ«LÊg³ó~ýµhÄPýƒ€¯¯±Xu‹‰""Ú] ››ܽ{·ÝG–;*“$ÁVì‹®ux§‡AwG3Ad`^¼x‘l!àÎ;×®]S”n'>>^flIÍfGEEݼy!tìØ1˜1cB(::ÚÄÄäÛo¿EåÿHª@6¿?@t:º~ýc{‰‚¼ààü5kBÂׯq EJ§KêêŽ7LŸ. BíZêþ‡~pvv®¨¨@‰Åb&“‰a‡ÃiÇCÈ/á^uÁVì’ØÎî-Ðí–9`öìÙDø˜¬1²UK† ¨Tjyyyc]ýn ‡Ã‰ˆˆàr¹Ë—/OHH7nœ›››Ï°aÃzöìID 3¦´´”Ø¿¥ak º UU0a<} ššpå ŒñÞö¢›7¥ÑÑ?þHe2ÍÖ¬ap8¼… U\\êýýi––Êb1`˜ê… í®ëÞ½{)))7oÞœ3gNVVŸÏ·µµÕÐЀ††.—Û•Â*[ŠÍƳÿ òBE¦{ïdó¢àÓˆÅâ¹sç:::*ž[Giii÷LSäp8¿üòËæÍ›B999```€ã8‡Ãquu%–3(hÈÑ 33”šÚøvqjjö®]ܼ<„P½=¨ýë/„端¸«VIóó;AÚÞ½{`îܹ¡Ó§O€ŸŸ±iæÌ™ÆÆÆ>ì²IC©ô” ;Äž-ä´OÁ‰fÒMÍÄ‹/V¯^}õêU²…|€=zÀÓ§OÉ"Çt“ÒU"‘hëÖ­&LJ¥<N§Óh´ºº:„Ðüùóùå¡°­ç º)Ïž!cc€PAAUyùËÓ§k“’BÕ#G"€ª;Bì-[¸S¦ˆ;ýΖ–zzzR©tíÚµ°sçN„о}ûˆ÷‰Î´Ý–Ÿ7[±³Ïwê׿›š‰   ˜4iÙB>@lllFFŽwª©ì2TVVÞ¸qãÉ“'d é@6oÞìêêZ[[‹277€ÔÔT„ÐÖ­[9BÔ•R  õܸÔÔßɉuý:B¨rñbPµd Bˆóë¯|WWÑ_‘«‘¨{àááÑÑÑ÷ïß§Ñh …è×ÕÉ [±£ü:õRÐMÍDYYÙÆ»ö-§{RWWJÄv¤R)QzíÚµ&&&ÏŸ?GYšÄóܹs×®]Sä_(hx<^Ùþý8Ž„={"Ö¨Q¡ºË—…ü~ [à[–,Y?þø#*‘’’bddDLq7GÌÅÏöâ[±Ùy7GÛMÍ„,SVVæîîÞ«W/²…È+l6[®çu‘·üí·ßjkk_¹r!4oÞ<8tèBèÖ­[wïÞåñx$ UÐ%‰D………¯^½BqöíéT€˜LÑÚµReeÁôéd ü0—.]€€©©éˆ#`Ô¨QÝd‰³I¬ç[±Ÿý¯óȺW9íwÉÍÍõõõ1cÙBÞÇÀÀ ===++‹Åb‘­E.!êVI$²…´€òòr"·bûöíêêêÇ …R[[K,ûí·)))Ë–-//¯#F0™Lr5+_p///ÏÍÍ@˜˜˜‘‘/^¨_¼ˆˆ¦»|>}ÿ~Š@ téôè3gÂîÝÕÕ$KÿoooF”«RQQ‰555 ‘ÁŽÐ¤`çK€¼01Â;éˆÝ÷÷®¦¦võêÕ¿ÿþ›Ëå’­å_P(”¸¸¸ÚÚZ===²µÈ%¯_¿¾v회7éÀq<#####8`llLÄŽ™™™I¥ÒÂÂBXµjUiiéwß}öööNNNŠîê Z B¨ººš0R©ôÑ£Giii‰D]]ÝÊÊÊÑÑwrž<¡44À³gpü8¬Xƒ99pálÚ£Fž,YBö©hii 8P*•2™ÌÜÜ\*•b``@¶.YÁÈöÿöî3.ÊkiølX¶P¥w¤#‚Q¤YMl±÷hÔ511MSÔäæ¾ML,ÉÆ *±cCDŠ ÒAD‘Þ·±,Ûß—ob£,,óÿåòåÙ1"Ìž3gFߊÜ^«lÌì£Uƒ±ÏÁÌÌì÷ß1bD?ì®íéé |>›C¿:.“É:::ÔÈÓ:;;³²²:::ÆwôèÑùóçOž<9>>ÞÓÓ³ë/zÆŒS§Ne³Ù@ì#ÔB¡°©©ÉÆÆ†J¥fffvvvš™™éëëÛÚÚêèè(•Jðõõýó4øø€,Yòøžº:ÈÎ~ü_z:ØÙ©ãÏñ7&L˜pëÖ-bjãÿýßÿa“ž¿ ýk´‚%e§dfA}ñ‹ž¤R©úàmú³¦¦¦þ–ÏæääÄÆÆ:::Þ¼ySݱ <*•ª³³³ŸìˆÅâ7n477ÏŸ??%%eôèÑÞÞÞyyyååå!!!¯½öÚÞ½{‰ \u@=¥³³³¹¹ÙØØXGG'))‰ËåŽ9ÒÔÔôîÝ»2™ÌÁÁA__ÿ/-“D¯üò•™™I4ÒŽ={ö,Ž÷{Šð‘2>LH¥“fd1¨º½þ?gP'2™,<<<++«¡¡Åb©;œ?µ¶¶›™™ÕÔÔàà«‘H$J¥R-)…X,þí·ßÔ³ EKK‹®®.ƒÁÈÊʪ®®6l˜Ýƒx<ž££#±Ü¥I …©©©Avv¶æýézÄÅ©íÍ9ŠoéSz½/ðàÝæ¦¥¥E¡PòòòÆüO§X5244,//·µµÅ_9¯¦¢¢"//ÏÞÞÞÇǧoÞQ©Tþøã™™™‡¢P(«W¯‹Å~ø¡ÍÔ©S‡ÚÙÙ©««{ëÖ­¾‰ *•Š˜Ïd2KJJîß¿ïìììááaff&“É´µµ€èž®‘(Ê믿¾fÍÌ$þ‰ãT­æqù)Y$ƒze=zdbbÒO–ÄŸ"‰„B!nœ¿‚ÖÖÖ´´4kkëÞN&¶lÙróæMbd¼ƒƒCEEENNΰaþüòK}}ýE‹q8œ^ BíííR©”ÃáTVVæääXZZŽ1¢¹¹¹¨¨ÈÖÖÖ®ßÔ4ôöööWß²¤BUÜ¡RªššÂÐ3ïÝEîÁ¾„ncc£££“ššÊçóÕË_ÄÅÅ1™Ì÷Þ{OÝ Hgâĉ½”I|ýõ×^^^wîÜ€¤¤¤«W¯¦¥¥À§Ÿ~zðàAøüóÏ×­[‡™ê)‰„Ëå@ssó•+WòóóÀØØ˜Á`sÚŒÃÂÂU&˜I<›ƒdAU)¡<^ÖÛï5Ø“ ˜={ö¨Q£Nž<©î@þÂÕÕúÛ±Õ‚D"á„Baw®#—ˉ¿‚o¿ýÖÑÑ‘è“óðáÃÂÂB¢6öý÷ß?yòäèÑ£`ñâÅóçÏÇõ…BÑÖÖ.\HOO‡C§ÓõõõU*•žž^TT”‡‡‡º#Eý—ÃT-(?%…^Þ„ÀdÂÃÜœúÛÜjwww.—{æÌu2P•––&''?|øðe_ØÑÑA´ ûî»ïX,ÖîÝ»@$•——ß¾}Ö®]{ëÖ­wÞy&L˜0uêTL POQ©TÄ*©R©¼xñbrr²L&ÓÕÕ500`2™R©”B¡L˜0Áßß ªÐ‹°M¥›•Êæ\E¯¾&°hÑ¢û÷ïÏ›7OÝü™LÖ×׿{÷nee¥ºcŒŒŒ˜Læ VÃ466VTTÀX,ÖçŸÆÆÆ"‘èÞ½{°xñâ‚‚‚ÿûßàîîH£Ñz3|4¸ˆD"…B‰‰‰‰‰‰€L&3™L‹EôQˆŒŒ éoŸyPÿG¢€ýkZPvJÚ«o„ÉP©T±XwíÚ5uÇò[¶lqww'œ¢—ellñO¥ì*•êîÝ»ÄVÅéÓ§ÍÌÌÖ¬Y*•J À믿^__¿oß>°´´ôôôÄcº¨Éår¢é{ffæåË—›šš€Ífëéé ĨQ£ÂˆAV½2Çi4¨<'StöâVÇ >ÚåèÑ£K—.ŒŒŒŒŒTw,ò÷÷777ÇOÀ¯L"‘455ëÃÄ—o¼ñFfffPP««ëÝ»wGŒÁf³‰*¶   G4EÕÓÓë‡ÝQÑ€¦P( …––VIIIii©———½½½Ass³D"€aÆu嬸‘zË™Âq§´+ªå¶1½õ e° %´¶¶¾ñƳfÍz³´G=¢¨¨¨¤¤¤¾¾žÏçoܸ±±±ÑÌÌŒÁ`p¹\…Báãããïï¿oß>*SjÔ»är9•J}ôèQ^^ž——qÛÑÑÑÝÝ].—S(LPï)ùUr{S§e5bo}@Âd¢_‰D™™™ÎÎΖ––êŽe 9zôhzzúÇ\^^#‰êëëÍÌÌ¢££­­­¿ùæ›~"Tƒ IDATÕði$"hiiÉÊÊâp8---7oÞ$ÚB`uÔ—:ÛT'*LO7 ›¼tÚzñâEGGGggçg<÷€kkkûúë¯W¯^­î@þbÕªU§NRw À®]»bcc‰AÞ[¶lÙ½{wmmmhhèêÕ«7mÚDüÔ¾xñâÞ½{1“@½„ølÖÞÞ~åÊ•ääd Óéb±˜¨Âáp8111#FŒ2™Œ™ê3:’ÅšJg^® ³©©iÖ¬Y111ÄL¸gÀdâ1¶yóæ]»vÕÕÕ©;–?…††á,ò²wïÞ°°°ÌÌLHHH¸páÑ?jõêÕÛ·o·²²âóù .\³f±±±ºƒEš‰H d2YJJJBB‚J¥"±X,—Ëõôô"##£¢¢€L&-®ê{SiPvò%ºW>|ØÍÍíøñã`hhøì'ãnñc cóæÍC‡íW¿¹.\¸páBuGÑ_Èd2¶{÷îŸþù“O>yã7 nܸ‘””°fÍš7ÞxcäÈ‘°bÅ â%eee …KâQoÈÈÈhjj?~¼–––H$’H$ííí #<<\__Ÿ(ƒÀï=ÔXEдÙ$Þ}E[±‚ãþœU±ÊÊÊåË—_¾|™ø’D"=w ®Lüéý÷ßío'¹‹ŠŠ~øáâØØ`£P(ˆõá_ýÕÂÂâ›o¾€öööüü|b yÙ²eçÏŸ_¾|9DEEÍŸ?ßÂÂâÉ+˜™™ÙÛÛ÷« tÅÅÅ—.]"ZKÉd2¹\N4º Œe0À`0° õ+dØM¤@Ù©g-N(•Ê;wzzz^¾|™N§g‹˜Læs Õ1™ø‹µk×ZYY566ª;?­_¿~õêÕÄïÎÁ@ ”••ÀñãÇ™Læºuë@OO¯®®®¨¨f̘‘””´mÛ6ðññ‰‰‰yF „‰‰‰îq n*//¿zõ*±ÚÙÙÙÕ&ÕÛÛ;&&ÆÔÔX,äFýÑZûá©Rþ÷OÈÊÊ6lØš5kÚÛÛgÏž D©Äs÷8“‰§<|ø°¦¦&!!AÝüiâĉsæÌÑìÙ¡Äܬk×®q8œ·Þz ìííE"QUUL˜0áþýû¿ÿþ;ØØØŒ3æÅ½Ö××çääô·An¨ÿkhhHII!Z£Êd2¡PØÜÜ NNNááá```€eh 0ò¢°œ)mªÚO/NˆD¢5kÖØÚÚ&$$Èår±XL Âdâ¥}öÙgÙÙÙýªLaÅŠGŽ5j”ºéI …"'''.. ÍÌÌfΜ ^^^ZZZÄOg__ßÚÚZbÓŽÁ`üS/Ëçjhh¨¬¬ìW«M¨ßjkkKOO'ÖÀ¤RisssCCX[[‡††zyy€B”Ãd”ÿÏNÇÚµkwîÜ©T*W¬X‘——G"‘âââtuu—,Y/2~ 0ÿbøðáÐÜܬ¥¥E´Mì._¾œ’’²qãÆýH¡P¤§§ggg¯]»V øûûkkk¿þúënnn–––...&&&|>ŸX+¦R©æææÝ_+++ƒ¡ÙK;¨;:::JKKI$’J¥jhh‰DfffÄ™®®.Ñ#¡Í~2-g[gu¢LÂUi³ÿ,ëY¿~}NNÎ÷ß"“ÉÞ}÷]øàƒˆ̸2ñ*6oÞlnn~àÀuò§uëÖ}õÕWÙÙÙêäUÄÇÇôÑG‰„D"½öÚkï¾ûnUU›ÍŽ>>xHo0S©T£Óé}\E(—Ë›ššÌÍÍ/\¸°`Á‚ &>|˜D"2¦M›æìììçç~~~Äþ©¸¸¸®®.((+15IGGGmm­®®®……ESSÓ½{÷$‰‘‘‘•••®®.ñ]:€Šê=É«:j’ämw•#ÿM7õ£2lÈÂGÊú4¹¨^ ºCÈ{öì)..¶µµÝ°aC׫¼½½½½½_äúêÿMÙéêêö«Lxçwúæø|~MM»»{FFFddä°aÃRRR¬¬¬Z[[ïÝ»éééDÞ`aañTûê~«½½](¶´´`21ÐI$’††‰dmmÝÚÚZXXhjjjaa1dȹ\NT;cÛS„žä±\»éŽ¢ü”´£Aþ³®Ãd­¼ï:ËNI ìÈ Ökܸq#lݺõÅ[> k&þžB¡¸zõê¦M›ÔÈcÍÍÍ|ðÁ²eËzãâ=ºxñ"}ÚÃÃã믿îû·‹ÅÅÅÅ*•ª  ÀÜÜ< àâÅ‹ÄOá¡C‡ªT*@pîÜ9.—Û÷± Pb±X¡P¨; %“ÉZ[[U*ŸÏ?uêÔåË—U*•D"¹páBvv¶º£Chhnæ>|öìΨ(Õ!*€'ÿk¨>\ðå—ž66`kk[UUÕÚÚ:fÌÐÓÓ;}úô+¿3&ÏqúôiˆŒŒì›·ãóù7oÞT©T555ÚÚÚ&&&*•J P©T++«K—.€——þF|eJ¥’Çã©; B m‘J¥§OŸ>}ú´\.W*•—.]JMM•ÉdêŽ!&©RRªW­z0t¨ÔÈè©ìA¤£sE[»hÚ4ÕÙ³•éé €Ø+···ôèq ‰D²páB ‘HŸþù«‚ÛÏ!‘HÒÒÒBCC)J/½EyyyNNδiÓ¤R)‹Å’Éd\.—Á`XZZ$''WUUY[[wttܾ}{øðáÝ,»´”Jå… äryllì€kâÙ¯…B===2™Lœäœ0aN¿~ý:™Lö÷÷×ÓÓSw€i(©n߆ììºsç”YY"I¡øóQFKË ™Ìêõ×}W¯–ZZuÍâŸjZZš½½}RR’µµõ“þþûïß{ï=¥R¹dÉ’={ö¼ìOHL&^ˆT*­­­µ³³ë© æåå%''/X°€ÅbYYYÕÔÔܽ{×ÕÕ5,,L©Tîß¿ßÁÁA*•>ù}ðT<ÿôz¶ääd™L6bÄuÇ2ÀÈd2‰D¥RÓÒÒGellœ‘‘!†nhh¨R©°%%B=L¥êÌÉéLKc•—·^¹¢{ÿ>]©üóA‰äë[kk›*;Θ1|ölø‡ò¾®LÂÎÎîÆOe„øøøyóæuttDFFž8q‚Åb½Tœè9òòò˜L¦§§g7¯sûöí¯¾úª¬¬L¥R5 Î;§R©Þ|óÍèèèÜÜܹÈwß}Çf³¿ýöÛn3háÑK‘ËåR©T¥RÄÇÇë¢ùùùçÏŸ'ÆÍãÿO„žvïžêúõî\@RUUºm[õœ9ª‘#¥ººOî\(*õôTóæµ~öÙå+ þ÷åû÷ILLìºG  ìììºv7þVnn®••899•––¾xÌx4ôùÜÜÜæÏŸœ@¡P˜L¦»»û Ÿ¼~ýú©S§¦M›öý÷ß=z”Åb­\¹rúôé...ÄÉ‹ÿüç?/ “Éär¹ÅÅůø‡ôÈdrGG‡@ ÀÉÔÏ@_*///**rvvvuuÕÕÕ%“Éb±ÜÜÜ<==‰Eœu‚Ð_œ9óç• wîÀ‹/f·µñ/^,>tȤºÚ‘Ïת¯ïê'Hh"‘ªLMýÖ®í>ü¡¾¾³¿?P(€±ÿp±#GŽ\¿~½kd—P(ŒŽŽ~öšDŸŒŒŒI“&eggÇÇÇ=ºëÑGíÝ»×ÓÓsöìÙO½·9žC©T&%%ñùü'ï$‘HîîîÿÔ>òæÍ›ûöí‹ŠŠš;wî矾iÓ¦uëÖmÛ¶í?þHNNž5kV@7Žóòx<.—Ûƒ.ƒL&;þ<‰Dš8qbïÕÁ DDÑØØ˜mjj:|øðúúúŒŒ ___…BA"‘0u@èÉd°jüü3À‚°güó ©@ UPОœœ·oŸcc£Ù_›é©ØìT¥²ÝÅe† *__¹‰É‹W0455™››S(”ÆÆF‹ÕÞÞ>a„ÔÔT;;»¤¤¤œœ,‰æÌ™sæÌmmíÿüç?óæÍ#î?wîܤI“œœœîÝ»÷ÔO\™xŽäää§2 P©TEEEúúúæææ]OÛ¼ys@@ÀW_}õàÁƒC‡‰Åâ¹sç¾þúë cܸq0yòäÉ“'w3‹Åb±Z[[utt°ÌíÐh4 …"•Jqâ—J¥"‘H|>?##ƒN§=ZGG§³³S €©©iLL Qƒ‰BÏÒÐ3fÀÍ›@£Á?²eO=ÞÙÑQqá‚—+¿qãQ|¼µDú!ÄÃ::0|ø ¡Páã3fÃГӍÿ¾ðR•üñ‡B¡;vì+g §§÷Ç|ùå—_~ùå‚ Š‹‹¿þúk2™cooÿàÁƒ«W¯¿×ºàÊij…«W¯þÓ£MMM‡¶°°ˆ‹‹KJJ ÷÷÷¿}ûvMMÍÙ³gÃÃÇÚQ-_¾üçŸþí·ßfΜÙ×GšH $IFFFggç¸qãˆÕmmíñãÇ“Éd@€Õ©½„Œ ˜6 jkÁÔââà¿û%'O6^¼8JW—’—מž®ÿÄo[%€ÌÃC;<<]"Ñ9ÒsÚ4Z}¶‰ŒŒLLLÜ¿ÿôéÓ‰LÂÖÖöÆ/žItji•1™&±±&112šƒCo‡ôË/¿,]º4<<\&“=™I(•Êôôt‘HôÔÞÄ *++‹---µ³³;þü÷ßÿóÏ?¯]»vÇŽ]ÏÑüŸ¤ÝñÜqP}_¸ ¯¯O¥R‹‹‹¥Ri¿µf ÑhfffÖÖÖr¹\ݱô–û÷ï_¹r¥©© ::::;;[ZZÀ××7::ÚÐÐØl6f½”ŠŠŠ††ø÷ºuéL&‘Ithk[‹ÅºååÀdÖ– ôññ!‘Hûöí#Š«˜L<˳MèèèôY$O=z´‡‡ÇíÛ·ÕÀ@4lØ0 küU[[{óæÍªª*J¥íííDáêêI¬s2™Lœ˜ŠÐ‹kllüã?²²²`ýúõû÷ï¹<:)iÄ!t%%¦ „?´øõ×Ðë×­V®„ÿ–ç÷™ÖÖÖëׯ“H¤p8œ±cÇŽ;6((hÇŽ555cÆŒ‘Éd/~A¹\³iÓ¦ääd]]ÝË—//\¸P(¾óÎ;öööB¡ðرc]OÆÓÏÂd2 †P(üÛG=<<ú8ž.nnnµµµÿ{̽ ¹\^__/“ÉìííÕK·´´´”––:T"‘´´´èèèX[[ÛÙÙ™››³Ùl`2™ê¡äîÝ»qqqNNNsæÌ9vìØ»ï¾»téRoookkk*• TªÅµkZùù˜×®‘‹Š #22àÃÁÄÂÃ!2""  ³NŸ>-“Éôõõe2Y[[ÛþýûÀÂÂbêÔ©Ó§O~Ù]Ýœœœ‹/^¼x´µµBCCçÎ{ôèÑòòrøñÇ—-[FÔZaÍÄsH¥Ò«W¯J$’'ï$‘HÄá{uE%“Épº;ˆ‚Y;અBáƒh4š§§gcccZZ›Í ‹Å\.רØ¿7zqÄt‚œœœÍ›7;88lÛ¶->>~êÔ©ãÆ»téÒ;w6mÚ4iÒ¤7ß|óYWil$² HL„ªªÇwêëC[ôÕ¿Ç &à ¡{9D¡Pxýúõääääääüü|ÅWb( Nooo€ÄÄÄððpÀdâÝ»w¯¶¶V,S(===wwwb×YZ[[sss###ÕÆÀ•““Ã`0ìííD‰DrïÞ=©Têïï/®]»¦££M,±˜˜˜àæB/ˆÏç×ÔÔ¸»»çååM™2ÅÒÒòæÍ›ÙÙÙ~~~®®®wïÞmhhصkWHHÈ«•+Âýû :Žééðÿ—Ë555511é~ñ·ø|~jjêÍ›7“““³³³» Î^{í5b¶6&’J¥211iii©¬¬ìΙÔŸ)в²2 —ËÏŸ?¯R©ˆy§åååFFF¸ЋÉd™™™=š3g΃\\\¬­­+++›››MLL,,,ª««e2ÙÙ³gýüüè‰ñ²²²šššÑ£G÷Á µöööôôôääd" +,,tppÀdb š7o^mmíŽ;¼½½ÕË€$‹+++I$R/õ{e>lii6l•J½pá‚D"‰ŠŠb0•••l6{ÀíË Ô÷¤Réÿýßÿ•””=zT(²X,*•*h4𥥥““Ó¥K—ètzEE…]ý›º|vî„Û·ï}Lœ'NôÅûö¦ÎÎN±XÌf³1™@ƒ”H$º|ù²––Vll¬ºc†††ºº:==½7n´µµ›™™UVVÒh4SSSê?ŒFÇ300 “ÉsçνuëVnn®©©iSSÓÇmmmçÌ™Ãáp¾üòK‡£ž·nâd&…3gBz:p8pçŽz‚éøª'ݹs§ª«ô€Åb±Ùì––±X¬T*µµµŒŒ\\\z¤W±B¡(,,,))™5kV÷¯6éé鹺º²X,¢½tßÐÖÖV__Oœ¹¨ªªª©©a±XöööÎÎÎr¹œø‘7@W\êmííí¹¹¹>>> #"""))©¨¨ÈÍÍíþýû¹¹¹¡¡¡6l ÓéÄnàÑ£GÕnq1|ôÑãÛK—ž=ÿ÷ï …›7bcáÜ9õDØm˜Lô$___ccãììlâK¡PhddäêêJ¡PJKKÛÚÚª««ëêê‚‚‚LLLºù^þþþ0qâÄœ‡ŽžâêêÚÇïØÞÞ^WWg```ffV___ZZªR©Øl¶ “É$¾+Ìûüx:BB^^^jjjtt´½½}lllrrò… ¢££Ùl6…B¹ÿ¾››Û¶mÛètº——¼óÎ;êù¿¥òñíðp€qã k¹ÑÅåq2Ñ϶\_ &=‰L&?¹ê ««K|O‡Ã¹té’B¡P(ÙÙÙãÆëf™ŒžžÞ¤I“8NGG&¯F ”––êèèxzzöÞ»tvv644Ðh4 ‹æææ¢¢" 333 033SSSSSÓÞ‹¡*!!!>>~Ö¬YáááÛ·o?|ø0•J]¾|¹¿¿SSÑø‡~8tè®®.Œþï­þ%7÷ÏÛÆÆL&L™òø—Ç70™@Ï¥­­mjjZWWb±¸¡¡¡û@O:Õ¡ jÕÕÕ½‘LÈåòÆÆF™Lfkk+rrrØl¶………©©©­­í!Cà¿Óä{ö}¸äryGG‡Á±cÇvºòTõ!IDATìØ1þüU«VeddüòË/†††ááácÇŽíj4·uëÖ­[·/Ò ³z—ûçíÿ­ÒˆdÛi÷'òµ¶¶vÿ‚àÔ©S‡êþ¥'ƒáååÒ#WS*•Dµtvvfff«T*CCC+++⯮®®¯¯ïøÙ‡PïS*•%%%EEEpðàA&“¹qãFèèèÈÊÊJKK€É“'ïÙ³gáÂ…0wîÜcÇŽ;V­Q¿’gÒˆdW&úý‰qõ"‘¨ûlii™6mš‰‰Éüùó»µAˆD"9::vó"|>¿¹¹ÙÑÑ‘ð­R©,--õõõ-,,X,–R©¤P(Du B¨µµõêÕ«T*uÚ´i¿ÿþûìÙ³'MštæÌKKK¢<Lš4)==ÝÇÇ|||ˆÕ×_ÃþýP^þç=£FXX@MÍã{ìì€F&ÔÝ ±;0™è;OvZì‘y•vvv'Nôññ!ÚÁvÿ‚ƒPkkë½{÷ ííí_üÿ¡H$jmm577§R©éééb±ØØØ˜ÉdÚÚÚ’Éd…BA£Ñz5r„ŠºººüQ¥Rýë_ÿºwïÞ¬Y³|||¦M›æïïïääDY=z4Ç#Ê¿Œ‰Â ÀfÃÌ™ðË/ÐØøøžùóÁÊ žì8G¥‚³3©%Àž‚}&z—ËMJJ"n3Œ¨¨¨®‡ªªªîü÷T±™™Ypp°âCOËåMMMr¹¼«‹F344üÛÚX™LÖÜÜÌf³étúÍ›7[ZZ‚‚‚† RTT$‘Hœ F߆PÄårÙlvccãâÅ‹AJJJMM••‡Ã!ÎÉ/\¸0 `ݺuꎴùø@~þãÛ))ÐC[«ý ®Lô'g¿öÔ$…êê길8&“ùœ!4èH¥RbMõÉ~P2™¬©©ÉÄÄ„È'”Je[[›ŽŽŽ¾¾~~~~UU•···ƒƒƒ¹¹9F#^¨Æá±õ---ùùù"‘ÈÅÅ…Çãñù|‡sýúu‰DÂçó---·nÝêáá¡T*uuuãââÔ2êyX€Ùw:::ºnÿossóõë×^êšï¿ÿþž={z ¾A†ûd}õˆ:Jb¼{iiéÍ›7‰šJSSS###" ttt Òœ•X„^ÒüñÑGíø"##õôô´µµuuu«««i4ÚåË—kkk‰Âó÷ßüøñb¨z5¸2ÑwˆÏÁ@"‘ž¬ç‰D¥¥¥r¹œÇã½ì5ýüü–-[ÔcQR©´kœîÿ’H$•••&&&uuuDaeeeeeÕ‡1"Ô¿lß¾ýêÕ«{öì±µµýâ‹/ &Ož! y<ž©©é;wØl6ñü~ÚòõL&úHKKK×Ga¢¿ AKKkذaííí5]Ž/LOOï§Ÿ~ê±( ¢×Í?¡ÑhÄÇ)CCȈˆ¾ ¡þ¢¹¹YGG‡Á`¬_¿þÈ‘#GŽ OJJºtéÒíÛ·mmmçÎÛØØH4}ïzaW&ÜæèE"‘(---777'''==¸ÓØØ¸«-&F£ug6DFFƪU«ÔÜy^ãq$¸\îµk×ÊÊÊ`ÅŠ&&&'Ož€ŽŽŽúúúœœxûí·:Dôeùàƒ¶mÛæää¤Þ°QÿÉD/¢Ñh …¢¶¶öÑ£G$ÉÐÐpذa!!!=;²¢¢b×®]XÓôRž{ ”F£õM$©KIIÉ·ß~{õêUøú믣¢¢ˆÏ$vvvZZZMMM°fÍšüüüµk×ÀøñãçÍ›‡³cÐßÂmŽ^D§Óû`×pÔ¨Q›6mzò *z.---éÏES©ÔnNNA¨ÊÈÈØ½{·¯¯ïÚµkßÿýE‹EEEx{{ÀÊ•+×®]K$ܸöÐ-‚¼<07‰Èdøüs9RÝ1½4ü‰Ù‹”]câz“••ÕÆûà½4É?ÍÅ ‘H82i©TJ”a¥¦¦z{{Ï™3ZZZ>|öìY5jÔüùó‰îÔÓ¦MËËË[µjèëëc¼>uÿ>deÁ… píÁرPV¦î˜^&½¨Ï‚Sw(/ “ ±iÓ¦ßÿ}ïÞ½£ˆù¶¡éþýû‘‘‘,kĈYYYùùù^^^ÁÁÁ·nÝJNN=zt||<›Í ¤ÀõpôV¬• öìntR,ÀÔÍÍÍwïÞMMMUw ¡—–ðî»ïÀªU«¦OŸž’’–––ð믿¶´´ËœS¦L ÃLBsÈå°t)˜˜ÀÞ½1“¬™Ð+V¬˜5k–ŸŸŸºA=‡T*ÕÒÒ:tèÐÁƒW­Z5yòäS§NíÛ·ÏÞÞÞÓÓ322RKKKOO<Øu¶ˆ¨©D¨½æÏ‡3`Æ u‡òê(_|ñ…ºc@=ÀØØ˜ØXUw ¡§ÕÔÔðx<&“¹k×®èèh‰röìÙýû÷[ZZŽ;–B¡ØÚÚFEE™››9röìÙvvv€ÿ¢5_k+DDÀèÑàèeeÿà‰a®Lh޹sçcxp®BêÅårÓÓÓõôôÆŒóÃ?¬^½zùòå{öìÑ××omm%¶3¦M›æììLЉ‰‰‰‰QwÔHJJ 'rrþrgL œ?¯¦€^&šC$µ¶¶fggc2Pß«ªª:räˆÁªU«§OŸ=fÌOOO===bäý¤I“JJJœÀÕÕÕÕÕUÝQ#u 8§94GEE…®®®™™™ºAHóu>üøãi4ÚáÇïܹãïïïææV\\\YY9cÆŒ±cÇnÞ¼Y©TªT*ܰ@š “ MÃçó™L¦º£@HÓˆD¢²²2ooﺺºˆˆ©TZ^^ÞÔÔdjjÊ`0x<ž\.ÿì³Ïüýý±-„0™Ð …Â××÷îÝ»\.W___Ýá 4°)•Ê;wî¼ùæ›ííí‡L&  …BŒ‚«­­500ˆ÷ððprr" Ì}õì3¡9( F£ÓéB¤Riaaa[[¼ýöÛL&311òóó333333`Íš5»ví"ŽDíܹsïÞ½˜I ô\˜Lh”††&“éïï Nîß¿ÿÓO?åääÀ’%K¼¼¼âãã€F£‰ÅbbOð“O>IMMw†N™2ÅÓÓÖ®][VV¶téR066Æ™Ýõ쀩i´´´êëëëëë}}}Õ B½¢¼¼œËåúùù]¾|ù7ÞˆˆˆˆW©Tiiid2¾øâ‹°°0ˆŠŠŠŠŠRwÈi8<Í¡i222‚‚‚¼¼¼òóóÕ B=£½½ýêÕ«<oÑ¢E)))£G>|ø;wJJJÜÜÜ|||rssÁõë×ýüü,--Õ/Bƒ&šF,ÛÙÙž:u ψ¢K lß¾½¾¾þ§Ÿ~ªªª²±±122jnn …666/^$Î.6Bj„ÉBHý¸\.›Í–J¥3fÌ()))..V(2™ŒËåLœ8ÑÉÉé믿ÖÑÑQw°¡§a2¡:::rssµ´´üýýÕ BÏçggg‡„„hiiy{{466š˜˜ØÛÛ?|ø°°°ÐÃÃcïÞ½æææQQQt:]Ýñ"„žOsh óçχ„„|ñÅê¡¿ÈÌÌܱcGcc#GDD›Íf±X>€ß~û­²²ÒÃÖ/_>iÒ$Ì$êÿð4‡1b„«««»»»ºANœ8qáÂ…Õ«Wûúú]«­­­§Nfdd$•Jà?þ`±XÄx‹ÀÀ@u‡Œzi˜Lh [[Û»wïª; 4èÈd2‰D¢¯¯¿wïÞŸ~úéÃ?œ9sæõë×<èåååëë;}út'''¢;õ?þØõB6›­¶ B=·94S]]Ý‘#Gnݺ¥î@& …7oÞ$!ûí· ãûï¿.—›——G|ûÍ›7ï—_~!:U/^¼xçÎÇWoØ¡‡É„f:~üø¼yó~ýõWu‚4Meeå?üpâÄ 8pà@hhèÎ;`È! …¢©© æÎ›••µuëV^²d žÞDH³a2¡™BCC'Nœ8bÄu‚4Á½{÷Þ|óÍO?ýòóóW¯^ýóÏ?€¿¿¿›››……L™2E +VVV~~~ZZZê !Ôgðh(BèOr¹¼¶¶ÖÆÆæÞ½{óæÍÓ××OJJÊËË6l˜““Óýû÷ëëë×­[úÖ[o©;X„PÉ„ÆÊÌ̼víZll¬···ºcAý—R©¼wï^YYÙ¤I“ª««]\\8NMMM[[›‘‘NJ¥rûöí~~~êŽ!Ôái·}ûv¹\ŽÉzŠR©Œ‹‹+((øê«¯:;;½¼¼Èd²@ °´´ÔÒÒR©T|>ŸÃá\»vÍÓÓ“B¡P(”?üPÝQ#„ú/L&4Öøñã¥Ré˜1cÔê/¾üòËÔÔÔ'N°X¬÷Þ{¯¾¾~É’%£F¢Óémmmæææ>ì:¨®Þ€Bns ¤êêêØl6N_ºté™3g===ƒ‚‚222ÃÃÃÿýï“H¤ ˜ššª;X„Ѐ‡§94Ù‰'-ZTVV¦î@P¯knnNHH¨©©€©S§ZXX$&&€P(lnn&ºVñÅ ~~~ðᇮ_¿3 „PÀdB“<""ÂÈÈHݱ žqíÚµ 6…BŸŸ~úiãÆ†††QQQ<¯££#44ÔÍÍ-44ô£>" oÙl6ƒÁPwÔ! ‡5õS|>¿½½ÝÂÂâüùó~øaddä÷ß¿ÿþ%K–̘1ãøñã§NŠŽŽ Sw°¡A Osh¸­[·^¿~ýøñãL&Sݱ ç‰DéééR©4&&æÌ™3¯¿þúĉÏž=«««{÷î]CCC;vìáljњ8c!ÔàÊ„† ¾uëVBBÂøñãÕ ú­­­¿þú«X,Þ¸qcfff`` §§gAAAyy¹»»{TTÔ¹sçÄbqYY™««+•ŠÙ?B¨?ÂdBÃ9sF¥R3†Åb©;R©TKK‹Ëå®^½º¹¹ùÒ¥KõõõæææL&“ËåJ$’ÿÝ»w€\.§Ñhê!„ž“ „z‘D")**>|¸D" (//okk#“Éb±¸µµ•Íf¯^½ÚÙÙyéÒ¥ÚÚÚêŽ!„^&®³³sÅŠt蔕•¥¤¤¤¥¥ÀâÅ‹wìØáïïß|óÍéÓ§‰Û¸‹ 0™Ð|555ááá#FŒPw ISSÓ™3g233à³Ï>³³³Û»w/Ðét>Ÿ_^^Ë–-»~ýúÛo¿ ¯½öÚÚµkÕ6B©nsh>ccãôôt…B!p.Ã3Ü¿ÿøñã666 ,8uêÔÊ•+çÏŸàíímeeE,í,^¼xÑ¢EÜÝÝqç!„ 0‰´´4wwwl5ñ$‰D¢­­]XXøÅ_XXXìܹóâÅ‹111cÆŒIJJÊÏÏß°aCLLÌòåËÕ)Bõw˜L "DÇ$uG¡6ÕÕÕÕÕÕÁÁÁãÇ·¶¶ÎÈÈ(**òôô´³³«¨¨hmmݱcGppptt´ºƒE¡“‰A!##cæÌ™®®® ꎥïH¥Ò+W®<|øðwÞyôè‘­­­±±qSS“@ `³ÙFFFuuu?|øp{{{uÇ‹B&ƒBMM•••µµõ£GÔKïR(ÿþ÷¿ ~ûí7™Lf`` P(x<ž¾¾¾­­­••Õ…  >|hkk‹]¼B¨G`21Xäçç{xxP(uÒ“ø|¾¾¾>…BY¼xqrrrff¦‘‘‘MUUUIIÉСC.\¨¯¯ÿÙgŸ™˜˜¨;X„ÒX˜L "`@ÿZ‰D¹¹¹,+::úÒ¥KÙÙÙÆ 5jTjjêåË—ÇŽ»gÏ*•:eÊbf7B¡Þ†}&‹cÇŽ±X¬O>ùDݼ´ÂÂÂ]»v•––À”)SFuãÆ àp8d2ùÁƒð¯ý+33344V¬X±téRÌ$B¨Ï`21XØÛÛK¥ÒÆÆFuòB®^½ºlÙ²K—.À?þ¸jÕ*¢tÔßßßÅÅE*•À¶mÛø|þo¼!!!#FŒÀ©›!¤Ø´j°ðóóãñxý°i•B¡‰D'OžÜ¶mÛo¼ñÞ{ïeeeýç?ÿÑÕÕ?~|LL ‰Dòöö€-[¶lÙ²…x¡™™™ZG!ô®L  …8ÅÐÐРÞH”JeiiiAA;vŒÉd~ðÁ ‘H233SSS`Ò¤I»wï^¶lq{ïÞ½aaaê !„Ð?ÁdbùôÓOííí‰}ŒËåÆÅÅ?~NŸ>=tèÐõë×€•••X,nii€ñãǧ¥¥9r<<;¿ÓØØ¸sçN©TºuëÖŠŠŠ3f :tæÌ™~~~ŽŽŽvvvÈãñ ÷Ml!„z Där9…Bé¥NMÍÍÍÆÆÆ­­­ ,hnnÎÌÌlnn611Ñ××çñx …bîܹÇ_¿~=¶ŠB! ƒÉÄàÒÞÞž‘‘áîî>dÈn^ª¬¬,77wúôé‰Ä¢½½] P©T‹% MLLvìØáââ2vìX*×ÀBHca21¸9r„F£0 ggç—zùÙ³g322>þøcƒaffÖØØHô¥vwwojjJKKsvvNMMµ³³³°°è¥?B¡þ“‰Á‚Ïç'''Ëåò'ï¤R©¡¡¡L&ó/ܹsçåË—wìØáììŠ!„ÐÀ„5ƒÂùóç‰yKKK+66V$Ñh4--­¾ !„ÀmŽAáÙ'3) èééa&Bè`21(<{·‘‘QŸE‚BHó`21(xzz’ÉÿwM&“‰œ!„ЫÁdbPÐÑÑ1bÄÿö±&“É#FŒÀÝ „BݘƒˆT*ÍÍÍmii‘ËåT*ÕÈÈhذa˜I „ê&L&B!Ô-¸ÍB¡nÁd!„BÝ‚ÉB!„º“ „Bu &!„êL&B!Ô-85tÀ¸sçNUUU×—,‹Íf·´´ˆÅb¥R©­­mddäââb`` Æ B BØgbÀP*•ÕÕÕÙÙÙÄ— ÅÎÎŽÃáP(”ÒÒÒ¶¶6âΠ  µFŠBhpÁmŽƒL&?¹ê ««ëååeii9dÈ   bò§B¡ÈÎÎV*•ê !„РƒÉ„&ÐÖÖ655%n‹ÅↆõƃBhPÁdBC0™Ì®Û­­­jŒ!„Ð`ƒÉ„† Óé]·E"‘#A!4Ø`2¡!ˆš ‚\.Wc$!„L&4Ä“§rÈdükE!Ôw°Ï„†Éd]·µµµ»ngggóx<:Nñpuu544TC|!„4&¢£££ë6‹ÅêºÝÞÞN"‘ ¤¤$555""B___ !"„ÒP¸®!ZZZˆ$iÈ!]÷:”È$ÀÒÒR¡P455©!>„Bš “ MÐÒÒÂår‰Û666ººº]uõŸb§ãÉRM„B¨ûp›c ‰Diiiººº*•ª¦¦†¸ÓØØØËËëŸ^ÂãñÈd26ÛF!Ô³0™¨h4šB¡¨­­•ÉdT*ÕÐÐÐÚÚÚÖÖ¶kSã)J¥²¬¬ÌÅÅåÉŽ!„P÷a21PÑéôÑ£G¿øóóóó9Ž««kï…„BhpÂdb zñi^*•*77—N§c&B¨7`21P½àìx¹\~çÎKKKKKËÞ !„Ðà„É„&“J¥©©©C† ¡ÑhÄÚÚÚO6¢@!„º “‰C©T …®/år¹@ Ð××Fól¡PÈãñx<Þ“wš™™÷b !„Ò ®–#µËÎÎ~ôèÑSw½T&B!Ôã0™@!„P·`L„Bu &!„ê–ÿ…èf&§É`IEND®B`‚opengv/doc/addons/images/nonoverlapping.png0000664016516101651610000011040513344612246020041 0ustar dimadima‰PNG  IHDRp½ÛaÃbKGDÿÿÿ ½§“ IDATxœìÝgXçà3[iK/‚(M:Rì`G£(bKì-ê5c#±`ïÆÆ$¶ ÆÞ"ŒvA@éEÚJYX–m3÷ÇDBР(ìPÎûÜßNÛ3ñîîáÌWŠ¢!„ªÜ½{÷Áƒb±˜¢(.—kff6dÈ===¦ãB¡OG`B‰B*sðàÁôôôjY,Ö„ ,--™ˆ!„ê‹éB¨¹¸sçλÙ$$yüøqÕǃBuJ„R‘û÷ïÿ×.©T­Ê`B¨aB‰B*R^^^ÃÞ—/_ª,„ª[˜P"„ŠÔÜg]*•ª,„ª[˜P"„аX5}å¨,„ª[˜P"„*TTT‚èܹ³Ê‚A¡º… %BÕ»¢¢¢Î;oÞ¼™.RQí'''¬P"„/L(B¨Q%“Éôôôììì ¼½½ù|~µÎ”...ÅÅÅsæÌ)++c*T„úd8±9BÕ—ìììÉ“'[ZZþüóÏ"‘ˆË媫«@tttJJJEE…‘‘Q»víèÚd@@À©S§ÆŒsìØ1¦G¡ÚÁ„!„êK\\\‡´µµŸ?nll\óÁ/_¾œ8qâ±cǬ¬¬D"‘¶¶¶j‚D¡Ï‡¼B¨ŽI$’ùóç'&&:;;?~<::úƒÙ$ØÙÙÝ¿ßÊÊêæÍ›-[¶Ÿ¿cÇ33³ÐÐP''§ `o%„Pƒ‚ %BÕBHHˆX,0`À×_lhhø™¤c¤‰Åâš~óæ A\.— ˆÏ|_„ªC˜P"„ÐÇÚ¼y³¯¯ï‚ `×®]~~~ŸͪsL*Šš5jÔ£GÖ¯_O’dPPPNNÎç€BŸJ„ú0‘H>>>ÚÚÚmÚ´©Ã+W}xÍb½ç;ùÅ‹7nܨ|éêêÊb±6oÞ¼zõjŸwÇñ „êaB‰B5¡(j÷îÝVVV/_¾tuuMOO_¸pa^_.—W¶ù|~µ½999¯^½z÷¬3fôéÓgçÎ,K*•Öa<!ô 0¡D¡šñðáÃÂÂÂsçÎÁ¿ÇÐÔ‰òòòʶ®®nÕ]b±8%%¥e˖¯¯Ú«W¯´´´6mÚlÚ´©n£B¡ZÁ„!„Þ/$$dÑ¢E°wïÞË—//Y²¤>ÞE(Ò ‚ LMM+·+•ʧOŸ¶k×î½ÏÁ+…††fgg‡„„|°ÿ%BÕœ‡!„Þ#??äÈ‘ååå ðöööõõ­w …EEEtÛ¢ê²ÑÑÑöööUÇ€¿×´iÓôôôzõêÅápBBBzöìùîÚ!Tß0¡D¡yöìÇsttܾ}{QQQ¯^½êöúb±øîÝ»EeeeÑŒŒ\]]+IIIÑÒÒ222ú˜ Ž1BBBüüüÜÝÝïÝ»Çãñê6f„ª&”!ô7nøùùÙÚÚ>zôhÆŒõñ\.W©TfggËår‡c``кukKKËÊ©% :wî\«ËÚÙÙÙÙÙ;³I„ê¸ÜB@II‰ŽŽNyyy»víúôé³mÛ655µººxQQÑ­[·è¶®®®··w ?zô(;;»ò%ý-M„‡‡‡¥¥e 'ŠD"mmm¥R9nܸñãÇ8°BG¡€J„‚Ë—/O:uëÖ­ãÇôè‘¶¶vý½×gŽlÛ¶­ƒƒCåË/^”””xzz~°?%öáÇOœ8ñòåKìO‰R L(B„Ba~~þ… Æ_¯Ù$ü{&ó÷RWW¯š;òx<‹õñQMž<933sÀ€©©©5G¡Ï‡ß2¡æëùóç£F’H$“&M:sæÌÉ“'™Ž¨Ô©S§ôôt//¯¡C‡~p‰p„úLX¡D5SEMš4)**ÊÑÑqåʕǯ§7"I²´´´ò¥B¡‰DZZZY8l׮ݧ½off¦T*%I²;ƒ"„Ð{á „P³“ŸŸÿüùó>}ú<}útß¾}Û·o¯×¾†‘‘‘éééÕ6öèÑ£þÞ”–””dbb"öîÝÛµkW77·ú~G„Pó„ %B¨yÉÉÉñðð‹ÅQQQ¶¶¶L‡£ ×®]0`€ŽŽNrr²¾¾>Óá „š |äj.d2I’¦¦¦>>>yyyZZZLG¤"={ö3fL·nÝôõõ¥R)ŸÏg:"„PSƒJ„P³?vìØŽ;þüóÏR©”ÇãUN$Þ|”——÷ìÙÓÝÝ}Ïž=8ÿ9B¨a…!Ô,PõòåK©TJO`Ît8ÌxüøqLLŒP(‰D†††L‡ƒj:pÚ „PS–——7xðàØØX''§k×®EFF6ÛlzöìzùòeCCÃû÷ïçææ2B¨‰ÀGÞ¡¦ì›o¾Ù¹sgïÞ½ÿúë/¦ci@¼¼¼tttîܹӲeK¦ÃA5zøÈ!ÔUTTœ8qbÒ¤IëÖ­“H$AAALGÔ°˜˜˜´k×®eË–fffLÇ‚j °B‰jj(ŠêÚµëýû÷;6f̦Ãi è1ïjÎ÷+VXXX|õÕWLG„jİB‰j:(Š*((066ž:ujaaa›6m˜Ž¨á¢GyÇ=;sÆ»,V~A±¿?ØÛ3B¨Q %B¨‰(NM]?n\Fn8555œpñ#帺š>N·)¢gOèÑzõ''h~3+!„> &”¡Fˆ¢ =!>þnäåQ_›nÝjß¾=Ó!6—.ÁàÁïÙnh=z@г'¸ºÂÇ­<Žjž0¡D5x˜‰‰ññ·ËËß=°´OŸ’C‡ÌÍÍUc#F’`k ))5£§=z@Ÿ>0m¨««*2„P£}(B [ElØ?üee8’ÍìÜ)Àl²¶X,˜=.¬é’kkðõÅl!ô^X¡D5yy°~=ìÛ2Ù3a>¬Â˜š¢"hÕ Äâ÷ìrsƒY³àË/¡Ù,}Žú˜P"„ôtX¹Ž¥²ú.ÁÒ’¨š†™3aÿþmÑÓSþü3 Æf³Š !Ôh`'k„Pãaa–Íž ï¦8_}…Ùäg™3ç_/55¡¨H2nÜ¢ÎE"C1!„ L(BY\üÈÁAk÷îêJ--Xº”¡ š èÝûŸ—óçK¼½µ¤Ò ‘‘ovîd.,„P〠%B¨‘ c¹ºvJL,¸=w.XXü³ë›oÀÄ„¹ÈšŠùóÿi÷ï¯~ýzÉøñ|«  ¢yóžEG3B¨¡Ã>”¡†Ž’JŸûø´ #”ݺźúúÂÀ`bII8d¤TΤ®EE@O ¿s',XJå9.·åzöd:J„PC„J„PÃöꕼsg×°09@úüùìðpW__GÇ¿ Äl²n°X@¯èݱ#T.24ožòÂ… o˜\Þ~ñbÈÏg0@„Pƒ… %B¨áŠŸ?Ÿôðà={&21‰Ø°Áâ‡þY ÐÁÀÜüïÕ‰©SACþ]†dûúò>$ÍÍÙ•µm»qâD’$™ !Ô0aB‰j ³==wì`‰ÅŠ)S´_½êø¯è„rùrœj».Àĉàí]m3ËÝõè‘ÂÝ]+?ÿ«#Gî¯]ËHt¡ ûP"„œ7çÎ|ó ddˆ8œ°±c<Èzw!i¡zö„˜˜÷L!„>Ç‹`eõþ4],.èßßèî]àpä[·øû›™™©<>„PC„ %B¨!‘Ë_ èÊ€=ÈÇY5Ì.yý:ôë§²ÐEÁªU°j:DD´usc:&„ó0¡D5II0v,<~,¸Ö­Û °0¬>6L{÷ræÌáPT‰··ÎÅ‹ ©ÉtD!†aJ„Pƒ7o^¹ƒ<~ mÚ$:4("³ÉKmölååË @篿*Ú·?²nÓ!„†J„ÓŠŠ¨éÓ‰3g ¦K×ë×A `:&ô’’ÈY¯^½xºj•ïŠL„b &”!&¥9b²`†P¨ÔÖ¾2dˆï¡CÂÂ\/¯‰‰ © ÁÁ¤Ÿþó!Ô¬\·Ž¤¨©YYecÆ€\ÎtL!UÄ!¤j¯V¬àuéÂŽŒâΑ tu™ }‚`ÿ}Ù/¿(¸Ü6aaÊþý߸ÁtL!•ÂGÞ!*.†3àÔ)¸nlÜ=&FÝÄ„é˜PÝyð†…¼¼‘¼c‡ßܹL„RL(B*’|ø°ÆŒ¦2èê¦~÷]ë Ø81PÓ“šZè奟›Kêé±ÎŸ‡=˜!¤ ˜P"„êŸR kÖkÖ°H2ÞÀÀ12,,˜Ž Õ›ÒRéðáüÐPŠÇû¥K—/CB444˜Ž !T¿0¡DÕ¯7ËüýMÓÓÍþËË«ËåËÚÚL…ê™RIÍ›GìÙC„÷êÕ󯿀 ˜Ž !TpPB¨)áwébšž^jdwîx‡‡c6Ù,°ÙÄ?,]JDϰ0=:/-é˜Bõ+”¡z! _}¥yö,„š˜8……™980R¹«WaÔ(‰±ÙâààÞ£F1B¨^`B‰ª{ygÏ*ÇŒ1“É(--bÏrÜ8\@¥Ù¢bb ½¼ Äb±‰‰æ­[àèÈtD¡º‡_ñ¡:¥TÂÊ•&£F™ÉdQêê—/Ä ˜M6g„««þË—¥ööšyyT§NçfÌ I’é Bu +”¡:SYЯŸ}a!°Ù…³gsW­èé1jÄb7ΟW\êÛwÎ|ŽPÓ‚ %B¨Ž;&Ÿ>[^žÉá´¸y“‹¢j(*cêÔÖÌKnÛÆâp˜Ž !T70¡D}.Yaá«/¾pŽŠ€8WWíààV..L…(ê×_‰Y³@.LCC;ub:"„PÀ„!ôyîÝ+èßߨ¬LÊåòù&L`: ÔàݼY6`€–\žcllúä ´jÅt@¡Ï…=åBŸJ©,œ;zö4*+‹ÑÒzyú4f“è£ôéËŽ.266Íχ.]žìßÏt@¡Ï…J„ЧP¤¥%têäRPl6,[Ë–ö‡CµRXÇÃíÛb€ cÿøƒé€BŸ+”¡Z£Ž縻»¼f±­[+Wb6‰jM_®]{åé© 0öÔ)X¹’é€BŸ+”¡ZÆtëÖ!>”þþkÖ´°·g:(Ô˜QTÙŠZë×IÞ²±qøë/ÓÖ­™Ž !Tk˜P"„>ZT”Üߟ›’RP²~}Ëï¾c: ÔTœ:%3†§TÆ»&&‚®.Ó!„jy#„>I>4ˆêÔ‰›’Rlmzêf“¨.ùû‹/]*QSsÍχN„÷ï3B¨v°B‰úììì>}Z&&’Ô²eì  ì1‰êEj* /^Äíyó†mßÎt@¡…J„PMR¶ow÷–‰‰<ÞíeËØkÖ`6‰ê‹•J„пPJå£ÉŽ!!<<„W¯úâŒÓHõæÍËÞ¿¿ŒÅê‘› }ú¹¹L„ª >òFUñú59nëÖ- fÈ÷S§€Ëe:&Ô|‘Ïž±†ŒŒ,/kß¾.“'3Bèý°B‰ú[ôêÕ¬[·ÆÆË–¹Ÿ?Ù$bËÍ <È655—É\§O§®\a:"„Ðûa…! ­wù2ˆ½½5Oœ##¦cBèoTYYŠ——ÍóçÀá$}ýµõÖ­,VCjXð3‰Ps—~áÙ¾½ÞåË2çâˆê7n`6‰BKËæÙ3 …¢Íöí×)¥’é Bÿ‚J„š1’Œ8Ñö÷ßùàîÇŽ£#Ó1!ôŸâ-j³u+† ƒ£GAS“éˆBÄ¡fŠÌÊbMž ¡¡$@ˆ‹K¿û÷¹8Ûjð OÒÿê+(*ÊÔ×—œŽÙ$jôýýáÑ£B#£V……º>>äãÇLG„À %BÍNy9ÌŸOýü3Óºµë“'Øc5:Òœœôöíírr@S³xÏ݉™Ž¡æ+”5#—. ­¬àçŸ P§¤$Ì&QcÄ75µKM… @,Ö™4éj—.J¦ƒ£°B‰Pó@QòmÛÈÅ‹ùUla¡{å 891BŸ‡¢žïÌ §LaíÛ‡3§"ĬP"Ôô Ÿ?/ëÖ»h঳3ûñcÌ&QS@mÿ=yýzPWgýö[¶›[þË—LÇ„P3…J„š¸ŒŸ~Ò˜3Ç$©-ˆÃ‡¡_?¦#B¨®=xPáã£VR’Æå¶ˆŒTkÛ–é€jv0¡D¨É’ó–,€¢îëë[‡…™à-j¢Š¢¢Jºw·,/òôiV¯^LG„PóB<~ü8##£òµ®®®žžžP(”H$$Iòù|CCC{{{mmm£DÕVú¥KŠ€›Š àóË–/× d±ÙL…P="KJX_~ þ)g±îLšÔû×_™Ž¡f„P*•™™™‘‘‘ôk6›mee¥¯¯Ïf³ éžžžÆÆÆŒ†Šú8»v)-bËå/ÕÔÚ=X,Þ† …ýú•¿yÃtL5 5òæóù&&&t["‘äææª$$„ЧºrÜÝ23Eâtㆧ™DÍO—ãlj?ÿ$µ´ôCC“--EIILG„PÓ÷iƒttt*Ûoðï<„*yYÙk4HW*}ldTýû3BÌññIûý÷×NÛ²2íþý!>žé€jâ>Pª««W¶Åbq=ƒúg›>Mq¹°cGǼ¼Ö;2B ³2„óä Ù®¤¤HÝÝ#×®e:"„š2NÍ»ÙU†…*Šz!ôŸ ŵk×nÞ¼©¯¯ß¿ÿŽoSFŶmjË—ÛH$‰<ì0r$³q"Ôp»¹AxxÞ_˜Ü¿ï¶|y)—+X²„é jš>PV¥’Åú»œUXX¨®®N’$EQ8¡zµ~ýúU«VÉd2úåòåË ïÞmðí·sr@1{¶YP?‰U£©i|çNh}ïÞJ’“y{ö°ß®ÐXVV¦¥¥Ål€5 xä-—Ë+Û|>ŸnˆD"ooï®]»vïÞÝØØøÞ½{¥¥¥ÿu’$+BŸ`Ó¦MK—.­ö9 …CÆãææŠ¢`çNΞ=˜M"ô^‹Õ÷ÎøõWàrÕˆ23»sýº££#Çl6ÛÈÈhÇŽL‡‰Pãö eyyye[WW—nØÚÚVV+ÍÍÍ_¼x! AÕI’¼téR\\ý+ÈápÌÍÍG­¦¦V—á#ÔÔ)ŠåË—¿—R`dtûܹ–]»ª8*„Ÿ)S’ÊÊZ|óMdQÑÿ||È·ÏßH’ …óçÏ?{ö,³1"Ôx} B) éA¦¦¦t»eË–•ГSrß>>¨Ü¸{÷î§OŸVÖT EZZÚ¶mÛJJJê*t„šƒ#GŽT}PPMŠPhêé©Êxj¼ÚÌ›|ôè×äûÖ>wîÜþýûUBMCM ¥P(,**¢ÛÕ (*))IWW×Ì̬êö'NTžX•\.ÿ×ÂB¨6žÆ•+W²³³?uï¹y“¡C‡zyy1BñäÉ“ªc´i†††µšó_^¼x‘––¦P(ÌÌÌ\]]y<Þ»Çkhhp8KKËÌÌÌ»wïzyyÛ%í½‹”}¢ÔËòÒtòùOÒ>¿bB‰Ðçj@}°œœœ ‚‹Å“&M>|¸¹¹yZZš™™™¯¯oÍ£…Úµk·råÊ!C†À²eË233¿ýö[hѢŀºví <¸pá=¢h«´r IDATÏž=FFF«W¯€+W®lذ!&&F7‰P-ÉÅTÜ/Rp›Ç¯ÜèòŸ«Id\—¿yþŸk~ † ^®àddÙ¤2¦cAÿB)!fwdÝRàç¡Ï×€ÊJ&&&?þøãéÓ§ **ŠËåêèè9yòä;wîÔ|:Aæææôb<£G¾råÊØ±c`Ö¬YgΜ¡‹š2™L__Ÿî—yöìÙï¿ÿž¾ì·ß~kccsêÔ)xøðáÍ›7‹‹‹ëùvªIey²EAPðõûq<  fϦ}EÌ ,.ÁT¥aJ½,/I&  zGM³#„>FCL(«>|øëׯׯ_‡:tèÐ… àéÓ§5¯qü.›áÇÛÚÚÀúõëß¼y3~üxðóó›3gާ§'$$$¤¤¤Ð}=·nÝÚ·oß?ÿü6oÞßÝÝn¯ZµjÕªUt{ÇŽÑÑÑnnn T*Y,ý¸|Ó¦Mñññžžž-Z´èß¿¿P( vpp¸}û¶@ pvvæó«–úx¸4N÷úõk55µœœ.—;{öìAƒùúúÖëœÏ2™ŒËå±k×®˜˜˜]»vihhèêê–””äççµjÕ*+++55ÕÒÒrêÔ©<oݺuúúúFFFõjÚ^ý!»(±ÅóÚ¨Ît,èÃ\ròãÞÎÅ{ßĨ ÿ=ó¦!ÕK>+»³@¢mÅòX¨vûå>\6¬˜¥f=8_Öd::„«Fÿט™™YNNNll¬ššÚ7~þùçÛ·oûùù•––ÆÅÅuéÒ¥>Þ´rB͹sçVnÌÈȈ722R(nnn­[·–ËåG%IrÇŽEY[[s8œŒŒ @°yóf++«aÆq8þ_!„…ÊòdÛÙ|âmÙÁy:?ሠ‹”}ŽFЇòƒtuu»uë®®®[·n¥×Ú9s挧§ç¤I“T†¶¶vç΀Ãá\¾|9::šÅb‘$ùÇìÝ»—Ïç …B555'Š‹‹—,Y2yòd‹%•J---é©‘H’¼zõjFF†ÊÂF¡æ#墼4Ô¶dÙ û§`ÌÓ&'ñþÎ5BŸ Iý)fbb²`Áº]^^nddD'š6l¸zõêÊ•+{÷î­âø|þ°aÃè¶‘‘QAAD"¹\H’$‹ÅJNNNOOçñxAddd 0ÀÔÔôõë×………3fÌèСC`` R©‰Dzzz*Ž!„š J ÏvV€Ë,>ñïE¦œ¦ñãË^G(ò+L:6©_F„T£É~lfÏž=}útº‡èéÓ§£¢¢è…Å÷íÛ§¯¯ïçç§®ÎL/4ú}ŒŒ6lØ@o±³³KNN¦‡‹ÅboooSSSˆ?sæLzzz```ll¬»»{÷îÝÃÃÃsss9Ò±cGÕçÇ!Ôx)¥”©'(]ž¬œØxÂa}Ú¶m[¸víÚ˜1cFŒqúôé‡þ¼K—.ô4é ›Í¦K?ýôÓ¼yó`ܸqOž|üø1ˆîÜÕ¸§ŽmF¸U:ãIñŸ­ÂBu§ù&”Àb±è4kùòåGŽ™9s&ìÞ½{̘1?üð…ÂF:ñ»££ã¬Y³ºwïAAAeeeôÝ999=ºk×®ðäÉ“[·n½yó¶mÛÖ¦M›íÛ·Àï¿ÿ %±F¨²®2Ålˆäïþцj’šuBYI]]}üøñôÃb//¯öíÛ=FŽieeÅt€ŸKMMM ÀèÑ£?Þ¯_?XµjUhhèàÁƒ@CCÃÊÊŠ^¸üìÙ³›6mJLL€éÓ§^ºt ®^½zîÜ9:E}Ð\fer“¨Ôêu®qVÎÁ²r&cB¡ú eu³fÍzò䉕••X,ÎÊÊ …¶¶¶E 6ìÇlJ;ssó>}úÐSmܸ1%%¥ÿþ0cÆŒõë×{zz@FFÆ›7oèÑå[¶l>|8Ý1`æÌ™¾¾¾111÷úõk&ï¡©'ŸÁÈÀ‹ÏÓ 5‚Ð ˆMõ~êÿ1$©\ÕiƒBŸ©YŒòþ4ššš¯^½JNN><þ<=GT*½xñâ Aƒ˜šÉ²¾ùøøøøøÐí°°°‚‚]]]ðööÖÖÖ¦G”‡……%&&ÒSiN˜0!**êÞ½{žžž[·nU*•“&M211aðj üÔÕüÔÕ˜Ž!„ê&”5!‚ž¨ÒÅÅ%88X*•²ÙìóçÏôìÙ3,,¬¢¢‚Ëå6íyŒŒŒèÆÒ¥K+7ž9s&66ÖÞÞôôôÝÞ¶m[nnî˜1cÀÉÉI&“ݼyÓÂÂâìÙ³zzzžžžjjøãŠB55˜P~MMͱcÇÒm //¯#FÀO?ý´yóæõë×Ož<™ÑUÍÙÙ™Z¡¡¡tƒ¢¨5kÖ$&&¶jÕJ&“¥¦¦Êåò-Z$9~üøòòòââb555}}ýhjjÆÇÇ·nÝZSS“¹[iLð j&¤õ»Xò¥¦ºëÖ Ô8`BYk 0`ݾsçNnn.=Þeß¾}R©ôË/¿444d4@Æ1mÚ4ºÍãñD"QZZŸÏ/++ûòË/srrtttÞ¼ysíÚ5@ ¡¡!‘H\\\8ŽX,&bÁ‚ÖÖÖsçÎeö.BŒãD¼BnóZ´X[k†–¦z=¥•8mBuå|–3g΄‡‡4ˆ$ÉuëÖ}óÍ7IIIpûömzmîæŒËåÚÚÚ€––ÖÏ?ÿL§;¤=z” ˆüü|GGG‡“‘‘±sçέ[·@~~¾ŽŽ=BH"‘üñÇ8;BÍÍb „$¿)*±~÷Ci™+ó5lX¡ü\ô\ …b×®]¡¡¡;w‰D `±X™™™¸¬v5<¯S§NtÛÂÂâÙ³gt[]]}Æ ôÂ剉‰"‘¨¤¤Fíì웚š:cÆŒ=z,_¾¼¢¢"77ׂÀ'b5EÆlÖÖ&Qi®R¹ ¨d£¨t¡@0[ ©…y„$¬PÖ ‡3lذ={ö‘››Û®]»öíÛëé饧§[YY­Y³†éº-ZΟ?ºwï. Oœ8A 6Œîcz÷î]¸ÿ¾••UŸ>}àÕ«WK—.½zõ*£w€ªc µµ*ÓÇ%¹¤¸Ä";w¨TDbµ¡ʺgggwçÎ8þ|ZZ=IxTTÔ¦M›222˜°000°´´ww÷³gÏnÙ²ºtéråÊz°yIIIË–-­­­àáÇëׯ§WÑ<þ<›@ZZÚ¥K—233¼‘:†]¾PsbÈbÍ×Öªº¥$—‹ZfçÌ+*ÉU*?÷ ð…PÝÁGÞõECCæÎÛ©S'mmmøùçŸ÷ïß_RR²~ýúäädCCC¦ÃlL +‡C :tèСtÛÅÅ%((ÈÕÕóòòèùçÿüóÏ9sæL›6íÀ!!!GŽ6lX@@ݽ•J…PÍäUV›Þ{@1Y»åE$U«Ì¨œ¢¤µ IFQµê€H”ÔòJHЬM^&¦(ÙÇ.¡(Õ.£¨]¥e‡ÄåóšóZ,¬Œ Äû'¡úóZ©<$.¯ºÅÇ Ò ÕPÇ¿ jh0¡d^e@sssû1c:EGCHHM_—»wÃÿþ§ª› WÙ“rãÆ7n¤ÛAAAþþþtÿ‘H$•J[¶l [¶l‰ŽŽ~ðà‘‘ÑàÁƒ‹ŠŠ8àààpçÎCCÃ6mÚp8uüùÂ¥Q³²ITVÙáSI„8L(WW×CÇŽT ƒÁÛ²«c³á—_`Ò$•FÖ¼õêÕ«W¯^t;<<\*•òx<3fŒ›››££#a„ÔÔÔ„„{{û™3g ‚ÀÀ@ƒ‚‚‚Æ[ËDHÅr•ÊebpårƒtÃ0•D¨aIJááóáüyè×îÝ{wg‡‡Òظ…ê£BoÑËùÀâ*]¢££SRRÌÌÌH’tqqÑÒÒ²±±Q*•‡–J¥+V¬{{{’$SRRôõõ·nÝjaa1dÈ:7EUóCi™%‡½ZG{¦’5˜P6HššðçŸàí OŸVÛcôä øúJÛµãO™R>x°F«VŒˆª133333‚ .^¼Ho”ËåGŽIKKEEE$I¡¯¯/‹/^ÌårËËË•J¥‡‡‡……ÅùóçÙlöÝ»w­¬¬èK!Ôl):óxtušÈð7„šL(*]]¸u z÷®šSʺt¹^ZÚõåK½¨(ˆŠR›3'ÁÀÀ~Ý:bìXÀiº.—ëïïO·õôôŠ‹‹ @*•.X°@$±ÙìW¯^=þ¼¤¤„ÍfçäätëÖÍÀÀ@(–––Ι3ÇÙÙyñâÅEÉd²ÊÊ(BM`„†:ÓQ „jhÀttàÒ%°²ªÜÀ‹ÅÆêI$pãFFÏž‡7oˆ™3)#£'ÖÖ¯~øärãED÷¡Ô××ß²eËþýûÀÊÊ*!!!88D"Q·nݺté GŽ9vìÝVWWïÞ½;}‘„„„°°0¦n¡¦—^D¨î`BÙ°µl áá`iù÷Ë´46úömV‘œœ¿e ôí Ri‡ÔTÛ ÀÔ´dôèÌãÇ Õ‡Ã±··ïÖ­ØÛÛGDD\¾|,--:´hÑ"ÈÎÎæóùÚÚÚôïߣ‡‚‚‚ **ÊÃÃîÊYRRòìÙ3Ym–½A!„ê &” ž¹9üù'УƒKK¡¤¤rµµñÂ…pãÆËÐЋÞÞ;;xóFç?Z[lf+W*_½b,lôyŒŒŒ&NœHO~Ù·oß²²²£GÒ»lllè¹3ccc£££³²²àæÍ›îîî#FŒ€'Ož|ýõ×—.]¹\NÖrñC„B¨¶0¡l œœàêUÐÖÈÈxw¿}Ÿ>ƒoÞTOL„ØØÐöí X,ÝœXµŠeoo`P¸q#ˆDªŽÕ)6›]¹2g×®].\C† ¹{÷n`` (•J'''zBÓ{÷îýøãW®\€£G ‚¥K—Àóç󃃓’’» „RPPЮ]»ÊU BuÊF¢]; -­÷&”ÿpvîûä‰^y9ܸQáï_NQŽ……úß}&& ¶¶ñ«W“R©ª"FõNGGÇËËËÕÕüýýãââÖ¬Y½zõúá‡FéééåååêêêpþüùqãÆýòË/pàÀÞ½{Ÿ8q222’’’èµ(j’Ö®]ûôéS…BQu#®€P„²ñðò‚7 °ðƒrø|èÛWíäIQB³o¿…Aƒ(™Ì!)É1(ˆef¦˜:5ùðaümÂ\]]çÏŸOOƾjÕªÒÒÒyóæ€ƒƒÃèÑ£{ôè‘‘‘aaaùùù°sçN[[ÛÍ›7ÀñãÇ£¢¢˜¼„êÚÇ`„ L‚P“… e£Ò¥ Œõñ‡›ÚÛ»mÛ—.å|8L™2eéÒ¥ôÔE)))ÙÙÙ:::ô1¾¾¾÷îÝ€%K– >üéÓ§––†Y&jà”Je~~þÌ™3qa*„ê&”ÍŒ³³Çµk‘¨âÒ%?^ÂfÛ[ïÚææ¯Û·¶l™R"a:ÄFÏÀÀÀ××— ˆÄÄĪ»¤RiYYÙ¾}ûRSS­­­'Nœ˜ššúèÑ#GGÇÐÐÐÅ‹ûùùmذÏçŸ;wÎ××Wõýû÷ï¿víZ[[[ MMMõòò€®]»öíÛ×ÙÙBBBÎ;G;v¬‘‘Qxx8lß¾}ãÆ999ª4>ΟWšƯ  €ÇãÍž=»úœ‡¡:D¡fL˜™y}útåÀ‡CP €?¾èÔ)Š$™Ž®qËËË£?bU·3„B!ý2 üýý¿ÿþ{òíó#GŽÐ熇‡W=7é¬ìeqÄ|±jná¿ÄÅÅýñÇåååEõïß_[[;77—¢¨Ö­[@RREQnnn666tûÂ… >”J¥uðÞÏžQ+VPÎΟOEG×ÁQC’––¶{÷î©S§ÚÛÛ;¶ê®K—.iiiÍœ9“¢¨ØØØU«V7®S§N-Z´(++{ö왿¿¿±±±¾¾þ°aò²²ªž3}úôwß.+L~ȲøÆÄ²z½)„š L(EQTyRRˆÏK€N+)€O¾`•˜Èthý@944´êÆ'NtèСò¥¹¹9ôíÛ—¬’Á?}»ÞæáÇ«žÛ@Êÿ²sçÎyóæ) …BÁçóY,–X,¦(Š~hžŸŸOQÔàÁƒ§OŸ.‰(Šzõê•L&û¨K?yB}÷ek[ùÿOjÓ¦ú¼ÄŒÒÒÒ”””iÓ¦€žž^Õ]§OŸ¦?)))åååiii]»v€Þ½{Ÿ?¾ÿþGŽùõ×_MMMÀÍÍM¡P|ðí0¡D¨aB‰þ-66kܸ\«ò—û¥¶vÔĉT^Ó‘5>ôð—ß~û­êÆI“&ýúë¯t;55•þŒˆˆ¨z ýÎ;Wu{O(«*++{ñâEQb±xìØ±_|ñEQ"‘ˆ uuu¥R)“É8ŽšššT*%IráÂ…¨šUS$IÝ¿O-X@YZþ“GÒÿëÕ‹R*™º5Tß꣺ÿ^Ù·å‡,‹¯OÀ„¡:€}(Ñ¿9;·BN³þ½GŸOÓÀ ×ž=oÞ<[±‚<ƒTÅJ IDATtÈ£¼NbŸ:•Ïáz{;lØíÚ1&3´´´ 77×ÛÛÛÛÛ»ÚÞ¿þú«òÈËË›0aBYYYDD„‹‹‹ŠCm ÔÕaÇ5 &LøgÝù“'aÉ’Æçƒ³38;ÿ Ä(*¢ ™'zð@– ŸŸÏ**2)*ò€àÁ€ uuh×î©L‘ÝqÔ(Ï/¿|AŠrttÔÐÐPÝÍ¢*°ºP£ƒŸ:TG Üöì={”±±ìÓ§ó¶l1)/7¾~®_/iÙ2­cG›5k´šYžÄçó`Íš5_}õUµ]/_¾¤—É KLL”H$ÙÙÙ£Fš0aþVçé ¬Ypò$ÀùóÕÊ÷ÒÓƒöí¡}{ð÷ÿW–GÆÆRÉÉìôtÑýûZ¯_«I$p÷.\Âöí°}»‹•F’EŽŽÝ»‡ …Oe²/¾úÊiàÀ¢’@€ÿ@* ¢ê>ö¡D¨îà7#ªclpq1\ºôÞöíâãygÏêdg»egS.€—WfïÞ&ß|Ã{;“\ÓfbbráÂ…Áƒ¿»ëöíÛУG'N¨<®FH_þøüü`Îxø²²àÓ†ÚèéA·n¬·]ñ´@.‡ÌLHI)-{øP/'‡›™I¤¦Z@|<ÄÇ÷è—/Ÿ/ãp®K$#FX÷í{+==ßȨט1to?T·°ºP£CPwR;Ô(ÊÊn/[¦yöl—Ü\Ë@JàçÇŸ6 ||àí˜ÍæfܸqÁÁÁ›7o^´hÑÇŸ•r^1¿Üz(·ûöæú(6/¦N…>}`þüz|—·2!%%çî]å«Wf……¬üüwT;»{¹¹©ÑsÖ,óþýŸK¥&&XÈüÙÙÙææækÖ¬Y¶lYµ]/_¾´··×ÑÑñññ155¥«ûÆ û„êþë;ŠãÅfÝ8_Õ¬»Øj¦0¡DªRX˜¿woΦMno×Ú)f³ÓÚ·wß¶ þ=“\s`ii™žžÞ½{÷? J¥ÂÃáíéªST))âçÏÕSRX ¹÷îéæå©)ï9€ïá¡Ñ±cHbb‘žÞ€ÿýO¯[7 E©«««:æFK¡P\¹rå½Õý̘1ÃÏÏïâÅ‹Ÿù.˜P"T‡0¡Dª&yúTýÂÑž=ÚB!½EfcãàÐfõjÝæ1|'==ÝÒÒ’ ‘HTùØîc`BÙàA\\á;%OŸZ’$ñâ…2>žýî—*‡“NQi,V§Ñ£ÕÛ·¿’žÎ±³ë9q"SÌÚû´êþ{åÜU\'6íÊé÷;&”}.|(ƒTMÝÃ<<4¾ÿþáîÝ–›„†ò’“;$'SW®€—WI¿~¼)SÔ?2j Š“H]Û†¸Tpp0èééÕ*›À1 žtë¦ß­›þÛ ì·2ɤ¤”K—8/_Z’$¤¥Y¤…R GÂÑ£éCçÍsóp¡0ßÈhØ‚l[Ûg¥¥–ÞÞ:8kîܹÿ‘ƒj°B‰˜&•>Z»Vöë¯] …*D:/\C‡¾·“e1_‚Ká¡=؆Áð¯z(%¼:)‹Ý'-Ï%‡… 4MPNY\\¼víÚ½{÷J$9räÈ‘#Gõ‘§§\G|Sn=„Û}GS«PFnª°È5hË~ÿîÒȼ’×`ØZùKMµÑ}6©²³KîÝÓÉΖ%$¤ßºeœŸ¯#‘¼{`1Aè¶k§´°¸ž”Äquýâ›o([[¹šÇS}Ô Ð'W÷ß +”Õ!L(QƒQTD<³p¡kY]‰óx mÛÚ­Y#ðñ‚Èa0ì\¢ª”é\Áõ&Ü4CŠ„ôyÌniQ¢´-YÝ~Ð0òø¥jª eömEè$1`Þ›ãþÚ¿ÒÊÒ—ð× Îøg Á†63 ã^ÕÇYÇŠŠd ÙTr²µDREÆÇkä{(솭°±¹óúu //—€¨ëÇåeP¦µHÑò+Ê2I›á*Ítׯ_¿téR}}ý7oÞ|þÕšLBYQH½:!s˜Èãj{©P4¾¿ÍP† %jp2nÜh}÷®üàAnÆÛ4ÂÞþI›6K—Žð\ïžb@Þ>”‘ð›¢,‹}g¶û|~+o.|ô·k£ÐTJ…„zuBöü'©¤€ø?{÷ŵ†ü-,½Q)*Š€"v± `Á† vÅcŒQ5Mc°[®T¢W‚-Ø+؈"E‘& ½-Ûî‡õ&Æ€A†]žÿ‡üÖÙÙå ðî{æœCÆNÜ®ËT[ôæQU>ýÞš$U5¼ÆjõÜרAAa¡|%ö”«Wõ ÛJ¥ÒG8ÿÜӜǫnÑâaI ÇÚÚÉË«¢mÛ4 «Áƒßã¦Ì]´Ë‡|r)WJRñÚP›´ÓÜßò’ç×Eþ#Ì‹”ðÔ™ñ·µTõãÛì»û5Rš‚2ܧ*ÎOÈSglf¨t^ èÖþ/"­¢Ð”uÄåDD<52ìM}~#UãFK Ê %4QR‘(vÇÓ§­¢£©¼œˆŽ¹r'_‘ÔvþÐý‹&¯ûÑ 3×á3%,%唵 ”WÈž¯~ôaeþ«²ÒeêxAÅ•ZNghìsRoÕ˜ Ù!‰ž>­ˆÕyù2/$$ïæÍ–UUºEEô^¦˜Ãáµm[bfv¿¬Ì¨gÏ.ãÆ‘¥%YZ¾å½'ÒÄ øçqòù’¾üçñÄÑÛ…Ù¡b"RÑb:ÎR±'àk*ê7›Ò”9ˆ£¶ sÃÅD$Ðc:ÍtœUS·R\Bg,©úÍ]®*¹Ç’f³ßî> JhòÊÊÒ~ú©p׮ΊÂzÕv–^^‹ÀU)ºÖzë=“\â©Õí÷‡T´êú›’¯Á0u›áÆOµNoËpè_Õ™7ÅQ[«Z àu]þæ@•Š6SÇš§Æpë6JÉðèFÐꉸB–p¨:ÖW(,’Mû¾—WS{RÎf)9nkÄhM‰PXšyåŠvFF˪ªÜ{÷(.ÎXRÃÇ­"†)71iåì\¨§—"˜¸¸´<˜´´ˆè,M5¬ËCDâ¤Sz+ú«^ÿ³+IDjFŒÝBA»‰*<·#ÊPPÊÕZVJÅt\@²nÒ}eôSÒ´h¼  tPP‚ÂèLã(®¶gUªÔ./Í7°ã2oíPJªI\Y·ÿç¥T]Z×ïQ™LVëhüßI\U§·•IITö·3«‹d¥Ï¥*ºŒVë7/²ºDVÇå„Ä•2É?nÉ«9€˜Dålþ|˜ù£Þ[I*HÓÓÿºP¨ª*°µÍÑת§g>bD«#ÈȨ1C6q/““¹ ºYY‰/¾|ð £@ —•EUUD¤^ɯTÕöÂŽÔñÆ11»_ ps¸ÄÓdT´˜·)q•¬2WÆSeÔŒ•¡>~¤J&,&‰PFÿï4*œw÷­[H8n#›†Ü€ ”Ö¡…áHŽo)( ²Ìž]½x ¶+è8KÀ4f´F’$ºµ¤¢U^ÿMîÊz¬hsîIÿ*,|,©®ÔQQ«õ&‡âgêT(¨ª¢ˆˆD-ˆ( €¸Ü}ý$ Õ°a­‡/67×°³ã5ã5w ¬­ÉÚšˆ:ÌŸÿêPEEîݻϯ_—©lË «¤Â”Ó¢œû¯¶âð™êbYu±6 ÄU²Òt%¼."â©1âJ™°P–r²ÚÔ²è_>i‰K'(+t(Aa<£gdQ[Ù²ó‰¿åŠ ù%D¤aʱ§Ò~ª Ž7 * yAi1šß Ê'“ÐÓß«c}«‹’^­úä²ðkñ®šÏæ ȳH"ãË23yII÷¨þã'uuµ§Oåí·?‰‰ª[´PwrJÒÒ*63ëàá¡Ý³'q”¨Ïö¾ZQ«,ʪíÙ4 „BŠŸJcvU¥žÉ$Äá’ùp~‡é*ê-”äo/7Rrgi…±#·Ÿm=%“Ðóëâ„C²çR"Ò2çØ/XSaD¹tÊä-/Œ¹â >â+k/¯ÆJ Ê%(’-´å ªa¿µ14æ !=»$ŠÞñjJKŽóuƒÎʳ¥²”o–’ûO£U8<¢‹]¨0ú¯àóIj=¶†÷‰ž]½š}ýz>_õéÓô‹[ÿYÓ¿hk§ Ùzzí'OÖëׯºC•Ö­⺚¸Å´x7í®íÙÓtz,½ú.Ï’Æù “ŽVKª‰áù0~—eª:V _Væü!¾<¥¼EoÞУÊp¥DHIG…qûªË³¤D¤ß‰Ûe™Àlÿ¯»N›ReN¯•Ÿ™*""™ -X ›3‡£¥ÕH¹AY  s–ÎΧù/è…¼U©MÚ_ÑW+iåëçdßGn®*I“Ž¿¥¥¢­?-‰¿³c‡Zjª#Çäå½qN1‡£êè(èÓ'Z,VéÒÅÊÓSEW·.¬i“¸%µÌ£7ÿ6ˆ¨;u£°7*_Y©4å¿—’r9WéÆ0¢šÏ×_ýÅåÞOž„B"zÉ妻ºvõõ¥6mã@)  EõŒž™’© Õ<ª-“RÉS©Žµÿ¶û§Ô³¢[ŸVXŒâ÷ß©T¥¤š®Î(·Ç·§Â©í¾nqUÖË“²ÌÌèß~+ ë«§'‹þñ‡ê?yyki¶RÔ¿¥)(ﮨL¬¦×¸k˜É:Ow¼H\ñ׆ON;©ÝGDDB!¥|ú©UNÃuëV0a‚åòåÄÃŒ ø((†²”,‹ >ÔÏΆ†F>lZPжªêeë‰2ÕÔÚŽO¶¶QB¡‰»{+''¶òÖ»Š8M§ŸÑ³NÔÉ‹¼¬è߸–w++^ÈþGÿWTš‚2/Jrï›Êš»’5Ò³@ʽIÒj2êCm§¼±£L&{°w¯Ãýû‚À@ª¨ ¢*}}ÕÅ‹iÑ",¡o‚@a  l$¥¥Æüö› %¥«ŠŠøÞ=^~þ›çèé‰Û·-.æÚÙõýôSêÚ•4»(y2 ÕÚ S9÷Ä—'—·èÅú›ÂÿÛ5Ä¿…(/ïúŒoÜ0«®&"Ã$tèÐ~ËûÛvæ„f %€Â@AÉ–ªì좻w[dfÞ½›uõªuY™@,~ãœNnëÖv“&UYZ¦êë[ ®Ú%¦PHe\"«Q(SAÙ€¤Rºq#wÝ:ƒ›7å%«¬k×äÁƒ­¿ûŽi~¢à-PP( ”MHVVîÅ‹‰§O·,,´**’%$0%3 ¯cÇ’Ö­#*+õ]]¦Lyû¶Ú喝˜¦L¡}ûÈÔ´þß\Ù¡ |'ŽÓ;qÂúæMÊÏ'¢ >_}Ö,úì3êØ‘íhÐ$  P((›,™P˜uó&/:ÚäåË7nˆcbZ …oœ#ÒЈ•ɸööö“&[[ mlŒ­þýnÅ7p =}J‡SÿþõðnÍÉ‹ûâK“ÊMzò†CAYgBáÍåËÕýüºWW‘Œaž´n­·r¥Ñ‚ÄUä àƒ¡ PiçD7W´É° e“WXHqqOÏ˺zµcE…AF••½qJ©¦¦V¯^Yºº #GZŒõ>ã×[¶Ð_—KkÖÐ×_+ålô‚‚ò½‰D"NTgß¾ª}ûÔäU„¥å‹1c W®äš¼mùtPb(( J…Vš˜˜uö¬Q^ž~vvÎúYY*oüøåó_êëÇÊd-‡ i7iRž±±FçÎêÿz›ZBÂ_cŽƒÓáÃÔ¢Eƒ\€ÒAAùábnÝz¾n{r2¥¦Q5ÃÈF¬XA}û²  J…‚R©ˆD””Dññ 'O CCm¤RAVýýr1‘ÔÒR¯oß |“N“'ëwèPÃ[µkGÉɯÓáÃäêÚð ðPPÖ©4íÀ„eËÜÊÊ82¥êëËæÍ³\½šÔñê¹@A  0PP*¹ââ¬Ë—_ÛH$j©©¥·okýãFL25}¢¢òTUÕÎÛ»¥«kA‹º¦¦œ•+iË–¿ÎaZ¼˜6o&åÚ̾¾½_šXnÒƒ7ì8 Êz “ÉŠ##u+wïV+/'"ÒÕ­ž4‰³l¯];¶ÓAƒCA  0PP6/b±8!ÏÄÆ>9}Z;-ͤ¢â׫8œx"ë>}´ïÜyóåݺÑñãT/ó~” Ê’–˜xëóÏǤ¦êÄÅ‘”襃ƒÑ×_Ó¸q˜¸£ÄPP( ”ÍXL‰‰Ož, sTUå<~,‹Ë^õ2}}æàA¡««kUÖeƒ‹ˆ9rHNŽüV±‘ÑKK20`94ÌPòÚŸ›-lm;®^ítîçÄ Š‹crrŠ©S§Og hôh_-­––UUUDtâĉ'Ož ¤[·ÑÙÙOBBhûvI›6:yy–¿ü"kÕŠfÌFD°ê J…eb¢óìÅÇ×z‡ã ;–—«ªªæææzzzvïÞˆ*++çÌ™³sçÎÆ‹ÚáZ£p0€–,)Žˆ80yr˜¹9#ÓÿËqrÊ45¥_~¡ÊJ¶Bý@A  °îß§/¿¬á¸®.MœH‡Ó‹=+*|îÝ#¢ÒÒÒQ£F >œa˜øøøøùùQrr²®®î¸q㈨¬¬ìÚµk999{ üô g=Ú#-Ã~IÔ*'‡,›™¥xzJž>e; |(Ûà½Ò¤I$ýu¤];5ŠFŽ$ggâ½úñ®JdaaADVVVAAAòƒmÚ´ñ÷÷WQQ!¢ØØØâââÊÊJ"zðà««kŸ>}îÞ½›’’²ÿþ~ýú1¢‘¯ ”™••ÓµkQ÷ȸ¸XëÇ©U«77Id$Ûéà`È@q`üiìX;¶A¿‚­­­­­­üñªU«F¥¡¡ADb±ØÌÌLþÔ¹sç6mÚTYYiooÿóÏ?ŸŸŸœœ|êÔ©£G2 óâÅ aÆQUUÕÕ«W333Y¾hxFFF ·nµ¿p22ޏ¹=$R/)¡¥––™}ûJ¯\y‡OÞ§N5dÒfJhºŒŒŒˆ¨U«V§OŸþóÈ¡C‡äc߉‰‰¥¥¥DôèÑ#777;;»˜˜˜ôôtŸ>}ú̘1ƒÅðÐàTU§^¾œ˜˜X]PÀ÷÷¯Þ·¯Uh( J66Òùó9󿑿¿Ý »f 1 yx4J\e†%(}}ýéÓ§{{{QÿþýKJJŽ9BD2™làÀ}úô!¢ˆˆ__ßãÇѵk×ZµjµråJ"*((xôèQuu5›õ­C‡*½{WïÚu`õj?++jÛ–8Ë–UêëKæÎ¥ØØ·½X[›fΤ‡+¬ÒBA LSS³uëÖDÔ£Gààà½{÷‘­­íÆåEg\\\VVVqq1ÙÛÛÏœ9“ˆQqq ‹á¡ ‚¿ûn^r2¥¤DlØpžaTE"îþýdg—Û¾½èèQ‹kx™ž•–ÒÈ‘„›%> JP6íÛ·_±b…§§'-^¼899yÕªUDÄãñºtéÒ­[7"ºÿ>ÑÞ½{öíÛGD¹¹¹ùùùl¦‡Äát[¹²crrì©S´re¥ššñ“'ü©S©MZµêÍÂQ¾Ahf&¹¹QQ+y• JPfÇÊʪmÛ¶D4mÚ´¨¨¨Ï?ÿœˆìììˆHWW—ˆ¢¢¢bbbªªªˆhëÖ­FFF›6m"¢+W®øúú¦¤¤°˜Þ¥¥¥‡mØpíàÁï,,J­¬(;›6n·iS2l]»öê<=½WâãiêTºTï %4Gò>¥ŽŽmذáöíÛãÆ#"‡cllܾ}{"ò÷÷ÿè£nß¾MDß|ó››Û­[·ˆ(33S^}BÓ7ÊÓó»§Oµ’“%÷ïÿWMM$•j_¾L®®%ÖÖU;wþmÖÎ… 4o{I Jh–^[‡ROO¯_¿~-[¶$¢õë׿xñbìØ±D4jÔ¨3fôèуˆBBB®^½*‹‰hÞ¼yÚÚÚW®\!¢      "Œ–6yÜ=\Ÿ>=·u+}ýµÔÈH;%EuÉÙÎ;Éߟ¶mc) bCA P³)S¦ŒþÍ7ߌ3æÉ“'D4þ|ooïgÏžnÄl‚Z´há¹l­[—pãÆÒÎ#™²²7Oúâ úÿUPw((þ]‡<==µµµ‰èúõëåååíÚµ#¢ñãÇ{xxØÚÚщ'<(ß7ÒÉÉI[[;==ˆÎœ9óàÁ¶l2:uîüÓ… ]ŒkxN*¥©S),¬ÑC)6,l 8°S@ýùÀ½LUTTäÖ¬Y# •JŸ|øØ±c÷ïß_PPðøñã®]»ª««³y -'‡ôôèÌ™×+HRS{ýù-ªååíììtrsõõõïß¿ïììÅÆÆ…B" ž0a‚»»û¹sçbbbNœ81pà@ó+ž-húôºœ¨¡¡!¿{ˆ"""†100 ¢Û·o'&&N:Uíïe(  hBZ¶l9gÎùãY³f 4H&“Ã0ŽŽŽÝ»w'¢ëׯÿðÃùùù...ÿýï7nÜ8oÞ¼%K–dee•––ZYYñxøý^o>þøcù_éúõë/^¼X\\¼|ùr‰DÂårÙN×T`R€ÂøÀI© p†±°°°´´$¢qãÆEDDÈ'•÷ïßÿÇôð𠢨¨¨¸¸¸òòr"Ú·oŸÍ7ß|CD—/_Þ¶m[BB«W $LMMåwÄzyyõêÕkæÌ™Däìì_¾ÍÏÖ­['OžMDK–,™>}zRRåççËp{Í¿1224h:töìÙDäïïïââÂr¸F‡‚@É»¸¸èêêÑ™3gÊËË»téBDcÆŒ?~¼½½=:uêðáLj¨¥¥ODG޹téREE«WФõêÕëÒ¥KK–,!"ÿàà`ù–›·oßÎ~ûòéJ÷P4/|>_þ`åÊ•=;;ûþýûòò]¹¡C  8”å–/€¦Ë&¼ÁÁÁaòäɇËå&''ççç«««WVVzyy¹»»:uÊÏÏOMMM$éêê¶oß^$ѱcÇ¢¢¢0JNDÚÚÚsçÎ………mÛ¶µ··¯¬¬1bÄñãÇ•ø¯Jx“|²ººú/¿ü"?¢ªªzéÒ¥ÜÜ\.—›––&_—‘ÏçgffNž<ÙÈÈ(77·¸¸xöìÙŽŽŽ_ý5›é›CCÃßÿ½²²’Ãá;vìâÅ‹yyy'N,***))iÓ¦ Ûë:”ðïTUU‡*ŸBneeURRJDååå#GŽ:t(ÅÅÅ:uêÔ©SD¯§§7qâD"*))¹~ýú‹/X½È7Ô™:uê¡C‡~øá"òõõµ²²Ú°aÛÑê:”ðΆ144$¢öíÛŸ={V~ÐÊÊêÀòÝÆ“’’ŠŠŠäûF†††>|àÀÁÁÁñññ»wïvqq™0a‹ù“ŠŠÊôÿoù˜——Çår»víJD[¶láóù³fÍÒÖÖf5`=@‡ꇉ‰É¬Y³ä]ɱcÇÿüóÏDÄçóûõë׳gO" ݳgOPPýþûï;v”·ë^¼x/¿)S‰mÙ²%33ÓÍÍ­¢¢ÂÇÇç³Ï>{òä åçç³탠 €¡­­ÝªU+"=qâÄܹsõõõÙÎøС€fA&¡8?aа2q…ŒèÍu¸žž]ž\ž!a+^óÄårÛ·ooffFD .|ôè‘|¿™!C†,^¼X¾MDDDTT”D"!¢o¾ùF__ß¾}D´oß¾çÏŸ³zõcèС;vì ¢={ö¬\¹R¾Dhee%ÛÑê %4 —2CÄ…‰’øÕo<%“ÐÃíU9÷Äå™RV²ÁÜÝÝwîÜ)¿çÒ××788ØÍ͈ø|¾Aûöí‰h÷îÝóæÍ{øð!-^¼xøðá‘‘‘DôòåK©TñþµµµÛ¶mKDC‡=zô¢E‹ˆhþüù=zôˆˆˆ`9\  hê*rjþÉ(,’Iª0þ ðº,U%¢øýBQÙß¾wžž©.}&ÕmÏm;’ÏR4¨•ÁÀå3Ê÷ìÙ“ŸŸ/ß”ÜËËkÊ”)òéÒׯ_¿té—Ë%¢Q£FijjÊï¿ 8þ|YY«Wðn† òûï¿wéÒE(^½z5""B>ö}øðጌ ¶ÓÕ %@Ó%*—]™V4¼¬º´†Â1rSÕ©eY·Å @A;qMûò„E²Ç¿þÕ¤”I(z—ˆì üVTsçÎ=räˆ|¸< àØ±c666D$ «««---‰héÒ¥#GŽÌÍÍ%¢I“&Í™3'//ˆäÿmâAJJJPP……ERRÒÌ™3;uêÔd7UÇ·@ÓÅ×`dÉâ÷ ßxª$Mú$ º2_ªÕßÅï@Þ¤ŒóÊ樂É^µ'u¬9mÝÑžTT;wž8q¢|oñˆˆˆòòr‰D2cÆŒ &XXX…ÂS§N!¢+VtìØ1 €íP((š<‡%"Š?P-*u'¥¼=i1НÝßÂïLÞ¤”CUäÉíÉfÉÈȈˆZµjåïïïïïODæææ«W¯&¢'OžH$y§3**ÊÍÍmôèÑDôôéÓ>úèÈ‘#,&WQQ™8qb«V­$‰™™™®®î!CˆhòäÉ[¶l)//g%~4uò&¥¨L–qMLDâ Ú“Èþ1\’V“v[´'ˆHGGg„ Ó¦M#¢ÁƒË M‡ãæææââBD÷ïß÷õõ=yò$]¼xÑØØxÙ²eD”““sÿþýªªªÆ Ìår÷ïߟ™™©¯¯ÿþýcÇŽmÞ¼™ÇãI¥ÒØØØÆLB((‚¼I™~MLD¥iR´'>P‹^<“ž<™„ˆÈ~±íIø'--­Ö­[QïÞ½/_¾¼iÓ&"êÕ«—¯¯ï¼yóˆ(...//O,QPPP¯^½,X@DüñÇÚµkCCC'§ššuïÞýüùó›7o.\°³³›5kVãÃ/$ТÏØ‰'©’ñ5˜ò)Ã!»Ñžø ]>‘–9ÇrLS™xMŸ……Åüùó‡NDË–-{òäÉòåˉHEEÅÁÁ¡[·nDtñâÅ5kÖ\¼x‘ˆvïÞÝ¥Ky§3===99Y¾åO½ãp8#FŒ˜1ceddèèèÈ÷·<~üøš5k²³³⋾³¼ƒÈMuëyYŽˆ##²j%k•ÎÜŽíLЬE/ži_žõ´'áýp8kkkùcooooooùãaÆñxd; (—>}ú¬^½ºwïÞD´eË–[·nÉ'ôðx<##£Î;Ѿ}û,XðÇÑÊ•+‡*"ÏÈÈ(--ýð jjj2™lóæÍS¦Lñòò’H$=zôpttl éêŒL†­Ûš´O?¥]»j~jþ|òõmÜ4ŠoûvZ±‚D¢¿Ž˜™ÑõëÔ¾={™ ™9zôèíÛ·?ÿüs++«îÝ»‡‡‡ß¾}»_¿~®®®×¯_¿råÊ!C>¬ªªêêꪣ£óá_111qÀ€::: UUU>>>óæÍkӦ͇¿³ J€¦NEåo¿ù^Çã‘PHŒ4Ô™}ýu ÇJL$sóFÍ^vvv\\\Ÿ>}ÔÕÕû÷ïÿÇ$''›››wèÐ!))éádzgÏ–ÉdëÖ­kÕªU^^ž|Í£w% SSSmll80gΜ޽{‡†† …B>ŸÏùà_$((š´[·hÀ€·pþ<ÑXi\EikSm“"ºw§°°Æ ðîгzõêØØØß~ûÏçëè蔕•èééµlÙ²¼¼üñãÇ-[¶ô÷÷7330`À;mêµcÇwwwOOÏ 6ì߿۶m£Fúؘ”Ф%'è ð§={j­&‰(2²£ÔâÏÒpíÚµòR©ôæÍ›ÉÉÉzzzeeeG*•šššVUUÍ›7a˜²²2™LæååemmýÃ?ðx<¡P(_•½F]»výõ×_åÏ;—œœÌçó‰(((ÈÚÚºS§NïCeMÚ¿Àa„ îÞ>ÿF"¡üüÆŠPgÇÑÑÑËË‹ˆ455322ÒÓÓåu¤··÷øñãAZZÚ‰'<Èãñ 444‰¨ººúøñãoYç<$$äôéÓnnnÞÞÞ¶¶¶ ïJ€&mÐ âñH,®ùY.—ÜÝ7€"«½eóŠºz£äø0zzzDdhh¸oß>ù##£óçÏ—••ÑÓ§O¼C™0iÒ$›Çgdd¬\¹ràÀò…Ùåx<ÞØ±c‰¨²²rêÔ©III666ùùùýúõ›7ož|•Íו••…††fffÊd2SSÓÞ½{ëêê:”M‡Cÿ_Ú¬ÃxøTPgC‡¾íYUU” ¨455GŒ!ïb:99•––ž;wŽˆ$ÉðáÃå›}?|øðèÑ£DtçÎCCÃ>úˆˆòóóCBBd2Ù®]»._¾LD¿ýö[bbâÍ›7‰(==]¾¼]¹reëÖ­¡¡¡Ïž=KOO¿ÿþöíÛƒ‚‚J€¦Ïϲ²èÂ…7wÓ¸ô ÷í)“e#€âñô$--ªm™?ÆMÐ`8ŽuíÚõÂÿtéÒÅÏÏO>C<))éåË—"‘ˆˆ._¾If¤R""€ÜÝé·ßè]Ö]PN<¸råJŸ>} ´xñâÝ»woÞ¼yÑ¢E~~~ Sk݈‚@±‰~ù…»`‡(fÒ$ûß~c;@S%“ÑôétäH™†FîéÓ–®®D”MZZ¤©Év6€&I$%''ëë뛘˜>|8ù­ËÔq¿ûî»Æ õÛ­Û­´´6ÑÑ-bcI gg¶4E7zõ²¸t‰45UBBôþÿm¢¥…®$@­¸\®‘‘‘¦¦&iiiEGG¿ådÜC  ðüú«ÔÏ8úê«0L+ø‡«V¹„… ‰R¶m#''¶ã(ssó·lÏÈ0 JeÀ›;÷å¦MR¢gÎ<[°€í8MÉ¡C&›6Éæ ¬^[~êŽÃáØØØÃ0¯—ÿÑÂÂ%€’0X¾üæŒ2†1ÿåòña;@“ð`Ý:±·7ÉdÌ®]÷îe;€›0a‚±±ñsod2™žžÞ”)S0)@¹üú+Í™CRið!ƒ®^e; ›¤ááU½z©K$÷{ÞºÅv€&$<<<==ýÏ?êêêêééåççWVVJ¥R@`hhØ¡Cmmí7^*ß’GCCÃÉÉÉÙÙ™0Ë@ùįXa³y3‡¨tÕ*­õëÙŽÀ’¤$ê×òòvébÎárÙЄH¥ÒçÏŸGDDÈÿÈår-,,ôõõ¹\nbbbAAü`ïÞ½ëò†òP66m ™>]Æ0Z6ˆ¿ÿží8,È{ô(ÃÎŽòòhøð.aa¨&ÞÀáp^ï>ª««ÛÛÛ›™™É·çær¹D$‘H"""¤òõZÿõ *)°ÇåÐ!æÀâpxß}êîÎv€ÆUZ*6̬ºú‘¦¦,0ø|¶(@`bb"\YY™““S—W¡ PRÞÞ¡sæH‰ú\¸ Y»–í4DZYIcƘfe½444úãFCƒíDŠGGGçÏÇ/_¾¬ËKPP(­>¿ü¾p!q8Ü5k –/g;@ƒ“ˆDwÛµ£à`255 kѹ3Û‰’ššÚŸËËËëò”ʬÇþCGŽÈ8ýmÛB† a;@Ã*œ6Í93³ˆaÒýüÈ‚í8ŠŠûÚmÇb±¸./AA  ì&M ™;WB4ðúuZ·Ží4 E¶q£a@€TE%aýú6¸u༾ÐääååݸqãŸ7V¢ P~ƒ|}36l .—¾ý6qút¶ãÔ¿;sæÐªUÄårz­\ÉvÅ&‰þ|,äÊËË###SSS‹ŠŠþù”Í‚ùÊ•tø°”a:>6z4Ûqê“äܹ^þþ Ñ-//3†í8 ¯¢¢âÏǺººò***]»víØ±c/AA ÐlLštkþ|1Q³g1ö JCtó&wâDžL>thÿ£GÙŽ  òóóå†155•?æóùoläý:”ÍÈÀ½{Ë÷î%¾ý6jÜ8¶ã|¨„3gÊ\\¨¢‚æÌqºx‘í8Ê ??¿°°PþØÜÜ\]]½.¯â5d$hrt,¨VSãz{w=}ú‘——]@Û‰Þ×óç-gÎÔ–JC[´èãëKµ÷NàíÊËËïÞ½«®®.“É222䌌ìííëøèP4;*3f„-^,a»À@úá¶ã¼aN¡]R’meeMØ\àðù|‰D’™™ùìÙ3†a ºvíÚ¯_?¯®Gt(š£Þ;vÈzõ¢3hõê»wïö½t‰íDï ª¨(©cGû¢"™éíÛôÚ®ðÔÔÔú÷ïÿ!ï€%@3ÅLžübË1QßË—3æÏg;@I$UcÆØep¹9 šøpR©ôß%@óe²dIÈܹRÇÌϰß7(ˆêyótoÝkk—š:9±@¼¾’ùûAA Ь ñóã=J<­Ys {3B“w}à@©šïÊ•lÇhF ââââãã‰(99966öÅ‹>‹{(š½‰=zÔñÇû_¿^¾r¥ÆÆl¨™xûöÁ7oЉ,]Ú»gO¶ã(0©TZZZúçÅbqII‰¦¦æ-¾N_____¿¶g™or€Y¸p€Ÿ#‘¿üRàãÃv€7U9¢6s&I$}Ôm϶ã(¶ˆˆˆgÏž½qÐÐÐð½§æ  €ÿ;~\6u*#‘„ 808˜í4‰ùùçvŸ|¢FDk×Ò·ß²ÞÄýî»ïØÎMCçΡùù-ÃÂ,ÓÒ¤23hÛˆˆ(:Z×ËKU,¾nkkyü8Ûi ˜”é»sgÜ—_ÇY»öÅdz€ ¢¢ÈÝ]PU•Õ·ï€ÈH¶ã@Í0ä ÿpü¸tÊŽTzÛÅÅùúu¶Ó@óU˜’R`kk%Š â]ºD**l'€š¡C ÿ0qâõY³ÄDÎ7n”—óG¶ «ª–ýú+ªI€¦ %ÔÀuß¾Œ‰Ç£ï¿Ož0í8ÐìH«««=<4ãã«[¶ÔºuK·M¶ÀÛ`Èj%;~\:y2W&‹tuu¼r…í8Ð\ȤÒPk뾩©bÞ½{dmÍv"øèP@­˜‰Ö,9^½J«V±š ñ—_öMM-#Š]¿Õ$€B@‡þEåÁƒjsç’X1xp·kרŽJîåêÕ?ü@**·níøÉ'lÇ€:AA ÿ®êÐ!ÞÌ™<¢Ç£Fu b;(­ÛŸ~Úw×.ÃÐáÃ4e Ûq ®0ä ÿNuÆŒûŸ~*a˜ŽgÏÒÊ•lÇ%uõjŸÿü‡CtyÐ T“ŠJ¨³€š:•Äâ?œ{ߺÅvP*Ù.˜NžL%%Ï==ÍŽg†íDðС€:óòÊÞ²ELÔûöíœ3ØNÊ#3$DeÔ(*)OÚÕ$€B‡ÞMÈÇ÷÷õåH¥²Ï?g6of;(¾/„NN‚ŒŒúúviiªZZl€w†‚ÞÝÿǾoõìÙÿÞ=¶Ó€«ÈÍå"xôHعsõåËZ-[²Þ†¼àÝyyŬ\)&êÿ~åâÅl§E%©¨H¶µ@@€lÊF" qrøàÛi@‘äΜi|èéê¦øû[Ëvø èPÀðòº·x±˜h`x¸ìóÏÙN ㎇‡ñ¡CNB5  PPÀéýÓOq_M<³ukîÌ™lÇEðë¯ý~ÿ]Jº` Äv¨ò€ú(4‰#•†9;÷ÀšçP»g¾¾æ‹“H”ÿý÷†«W³ê:”P<=Ã>ûLLÔãömÂØ7Ô"åðaã… I$-_Žj@™ C õæÅîÝ&K—’X?|x§ ØŽMLb¢¸W/^QQ°…Å€'O8\.Û Þ C õÆä“OdGŽH¦ÓÅ‹¸7^“ÿèQõàÁ¼¢¢Ê¡CûÄÆ¢šP2(( >1^^1«VI¦[HƾA®,#£¨gO•ÌÌ2µÓ§êêl'€z†!o¨¢£Gù3g’XÖ¯_Û·ÙŽ¬ eC‡27o¦ªªÄÇk[X°ê:”PÿøS¦Tîß/&êqçNâÈ‘lÇÖÈÄâü!C˜›7©ukí{÷PM(+”Ð ÔfÌøcñb Ãt8ž–/¯õ<‘¨CAc»ß£‡á;Ujjtñ¢ƒÛq ¡  €†â¼s'7 €x<Ú¶í~¿~5Ÿ´n]ㆂFäãÓ+*ª’aâ·l![[¶Ó@Â=”а2wì0ùì3QÞ´iFÿýïßž++#zð€:ub)4”¸eËl·o'.·èÀÝéÓÙŽ JhX­–, [ºTÆå>,Y²äoÏ]¾LtêKÑ ¡D~û­ÍO?‘L&Ú¾Õ$@s€%4Š'hòd‹o::ög†ˆhÒ$:~œìí):ší|PîÜ‘¹º2UUÁýûºy“í4ÐС€F1aBÌ—_ЉDF -""*+£³g‰ˆbb(>žÝtðΞ=£ë×ÿyøù•+â‘#™ªªÊ¹s7~.` Jh$ök׆/_.ãrU÷ì©X°€ÎŸ§ŠŠWϰ ÞÝ•+´ÿÇ^FE©¸»óŠ‹ ]\Ôöîåpð+ ¹À74®'d“&1IžžžQa᫃vvÃj,xG^^tîef’žÞ«#2gg&>>FG§]jªÚŸÇ ÀÇGh\&DÍš%%ú«š$¢G(!½LðŽ$ºv*+éÈùaaa^L|<98XÆÅ¡šhnPP@cÉϧ}ûhøpǃkøÑƒQorÿ>É?øú‰ÅqvvF))E::tá‚f«V즀ÆÇc;(»’:¼Þ_.ŠIDATs†~û®]#±¸ÖÓiõêFŒàòåWbcéÞ=:pÀ133ŸÃ)>vL·eKV“;PP@«¬¤Š ‰èíwlÇÆÒãÇÔ±ccÅ‚píÚŸ §LÑKM% õsç d/° “r ±äçÓ©SH!!5·*¿ûŽÖ¬iôXðŽŠŠÈÈèõAÃH}}¹óæ± Ø…‚]-•åË- ²³YÌurâyz¾yaÈÎŽÜÜÈÕ•œIMdÀ”Àžü|:}še7n0 Ql,ÙÚ² Þjþ|òó{Û jjÔ¿?}ÿ=õìÙX™€e((  ÈÏò‚‚ÒÛ´9lnþÕW_±j×¶-={Vë³úú4c-X@66˜ X†‚šŠâââv––y&L`;Ô$>¾æ2G4> D\n£Ç–a–74:::{ýü.\¸àááÁv¨YePЛwG¶lIÞÞ4{6YY± št( É‘Éd .$¢={ö0 ÃvxE&“…õ|ù’ˆˆÇ£#hî\>œxèM4w(( É‰utt$¢ˆˆ;;;¶ãÀÿ …R]Ý,"½åË5-"SS¶@S‚š¢ÀÀ@™Læåå% Ûq€|||æe˜—'0€ƒ»$àïPP@Ó•ŸŸïêê:xðà-[¶°¥YÛ±cÇgŸ}fooÉE5 ÿÀa;@­"""âââΜ9STTÄv–fmúôé ðññA5 5B‡š´óçÏ;88˜™™=}úÔÒÒ’í8ÍΙ3gTUU‡ &•J9ô  f((@œ={ÖÓÓÓÛÛó¾SBBB×®]%Ixx¸½½=Ûq éÂZ dÿÇvæÅÆÆfÅŠEEE¨&àíСÅmooÏ0LPPÐèÑ£ÙŽ£äRSS}}}}||0Ì uÁýî»ïØÎðïZ´hÁ0ÌW_}µhÑ"‰DâââÂv"¥%•J|òäI>Ÿß¿¶ã€ÀGOP$ÎÎκºº}ûöe;ˆ2ãp8?ýôS¿~ý>ùä¶³€bÀ7(˜/^˜˜˜¼|ùòرc‹-b;ŽR‰DŸþùçŸÞºuk¶³€"Á¤P0&&&R©tøðá< …Ë–-c;‘òX·nÝÎ;ïܹŽÙôPw¸‡Ã0æææiii›6mRSSc;ŽòèÖ­ÛãÇ·lÙÒ²eK¶³€"Á7(*ùRÛ—.] Y¿~=:jÂÏÏÏÄÄÓçàý  VPP`aaQRRròäÉqãÆ±GQEFFöèуa˜øøøvíڱ¯¯ðàÁ«W¯zxx°E9::®]»–Ç㡚€÷ƒ%(©TúÑGihhlÛ¶ cßuñË/¿ìÚµKEE…í, ÀPP€2ˆ‰‰éÞ½;Ã0QQQ;vd;Žb‹Å666)))›6múâ‹/ØŽ %(‰   >Ÿ?|øðÒÒR---¶ã(†lÚ´éÈ‘#èPÀ‡@A J%##ÃÅÅeàÀ{÷îÅ>Ôµ)//Ÿ?þºuë,,,ØÎÊ?m@©$&&¦§§‡……•——³¥éZ½zõÑ£G§M›ÆvPèP€²¹yófçÎ =zÔ¹sgÌÑù§²²²?þxÍš5VVVlge€‚”SPPЄ æÏŸ¿k×.Ô”Z¶lY§NæÎËvP*X‡”“D"a|fþ›;wîüôÓOÀÕÕÕÜÜœí8 <ðÓ”Vtt´½½=9s+ŸËíÚµK__êÔ©l¥‚I9 ´†Y²dɸqã¾üòK¶ã°éêÕ«S§N …‹/F5 õ%(¹ &˜ššŽ9’í ¬ …sçÎ=zô¨¿¿?ÛY@9aÈ”_II‰¶¶vFFÆÁƒ¿úê«f8G'>>þСCëׯo†×%4 ‰¤K—.±±±Íj›Áôôtwww__ß>}ú°”†¼ Yàr¹Û·owvv^°`ÛYOllìÚµkÙJJhF¤R)‡Ã9þ|hhè?þÈvœWYY¹råÊÕ«W²” Jh^^¾|iaaQZZ4jÔ(¶ã4±X<~üø®]»~÷Ýwlg€f%4;v(¥R)Ã0Ê7OåÚµknnn::: &&&lÇ凂š)±X}òòò }컼¼¼]»vÙÙÙžžžlÇ€f%4w©©©ýû÷wuuÝ¿¿âÖ”ò‘î'Ož\¸paÉ’%lÇ€æEynx?III¹¹¹ÑÑÑååålgyOQQQ–––·oßn×®ªIh|(( ¹:tè¥K—®]»¦©©­ˆã6{÷î}ö왯¯/ÛA ™Â7À+'Nœ˜2eÊÂ… ·oß®(cßB¡P ˆÅâ;w~üñǪªªl'€æJ€WLLLTUU[·n­(ÕdYYYß¾}W­ZÅãñ–-[†jØ‚%À_ž>}jii)‹:4kÖ¬&^Y^¸paÔ¨Q¦¦¦111úúúlÇ€æ %À›fΜyèСeË–mݺ•í,µ’vŸ:uª}ûö;wf;4kòxÓüùó[·n=}út¶ƒÔjÅŠýúõËÍÍ7nªI` J€7õíÛ7..®K—.)))_~ùeSÉ)..>qâDtttLL ÛYˆˆxlhŠ´´´Äb±»»{bb¢±±ñÒ¥KÙNôJii©ŽŽÎÝ»wÆ Âv"t(jÃãñ¶oßîââ2gζ³¼rùòåÖ­[_¾|ÙÔÔt̘1lÇx%@­† výúummíÇ/^¼˜õ±ïÀÀÀâââ .°à ˜å ð/rss­­­KKK/^¼8lØ0V2”””hkkK¥Ò_ýuæÌ™\.—•5BA ðƒ>|¸téR‘HÄår9œFÞÉÎÎîÛ·ïˆ#vìØRš ”uUYY9vìX]]Ý#GŽðx7©ñòåËcÆŒ±µµ½uë–††F£}]€:BA PWQQQýúõSUU ·°°h„¯(‹«««ÕÕÕïܹӾ}{ccãFø¢ï %À;¸víš®®®““Snn®‘‘QƒîÍ(•J§M›öèÑ£‹/š™™5Üø@˜å ð† âäägoo?gΩTÚp_«   <<<555;;»á¾ À‡ÃÂæï,77·´´455U(ª©©5Ä—xñâ…‰‰ÉÝ»wºwïÞ_ ¾ C ðÎ |þüy55µ[·nÕ{Ÿrß¾}æææÇŽ322rvv®ß7¨w((ÞG=ÔÕÕ÷íÛ7pàÀyóæÕïýè‘‘‘B¡033³ß á`ÈàýuíÚÕÀÀ OŸ>õ5;G>ÒýóÏ?6lôèÑõòž ³¼>ˆ¼ …{öìùôÓO?dÍó„„gggwww???>Ÿ_!†¼>ˆ‰‰ Íœ9séÒ¥_|ñŇ¼UZZZyyyVV>ê€bA‡ ܽ{wöìÙ¿ÿþ»Í{¼¼¤¤¤ººÚÐÐ0<<ÜÆÆFSS³Þ4”õC( ‚„„„_ýÕÇǧîcßUUUÇÏÊʺtéRãlÀP¿0) ~‘H4räÈ””SSÓ%K–Ôñ…eee………%%% ºï@ÃA‡ >ݺuk÷î݇RUU­Ëù)))VVV………vvv  !`R@}êß¿@@€ªªêºuë<==E"Ñ[NÞ¼y³­­í‰'ôôôPM€âÂ÷ÿÚ»—–TÞŽã^²A‘2/¥0X­4©¥.‚.ЪE½„–½”ÞF¯¢]í4m“‚”E–â%qtƳ˜?"õ?ÃqžŒïgõÌã,~Ë_=—ã=??Ÿžž¶ÛíËË˽½½ß½V­Vûý¾ªªffñä B\\\ÜÞÞžœœ(Šâr¹²Ùl©Tj6›Á`0‘Hôz½D"áp8 …ÂÆÆ†Õa`"J¨×믯¯+Š2šÔߋų³3.0ð°‡Êçóñx\Q”O'¸‡Ãáææ&mÀÏ@¡*•оEr|9Hw»ÝëëkË’€q(” P¹\þæ×B¡`Z‡B oüªÕj™–Ä¡P€@߀Q’$Ó’€8J( }ó+_îð3P(@ ýýýß}¡Ûétnoo›œD P€@Ñh4N·Û퇇‡³³³æGÃq±9W.—ÏÏÏëõú`0p¹\ápøàà X ŒA¡ÀDXòÀD(”˜…™±:üÙlöááaôèóùjµZ·ÛÕ4M’¤`0‹Åæææ, "p(Œ¡iZ¥RÉårú£Óé\]]õûýN§óîîîýý]ŸL¥R‹‹‹–&ƒ±ä Æp8ãÿ}ôx<ÉdR–åH$’J¥œN§ÍfSU5—Ëišf]L0…„“$iiiIw»Ý——kó€±(”`†ùùùÑøííÍÂ$`8 %˜ÁívÆNÇÂ$`8 %˜AßC© &Ãqm˜aüJ ‡ã¿?æs¹\£Ñp»Ýú1µµ5>ð `Q(À ý~4–$I´Ûí»Ýn³ÙŠÅb&“ÙÝÝõz½ÖD€Å’7˜áããc4öù|ú ëmÒf³É²¬ªêëë«á`2J0C­VÓv»=‰èãÑ]B6›M_õßj Ó‚B ÂÕjµz½®———=Ï×w†Ãáà#:¦{(@ˆN§suuåñx†Ãáãã£> …’Éä×—5M+•J±Xlüv!˜JÂår©ªúôôÔï÷gff@4]YYmšwssã÷û×ÖÖÌÏ “£P€n·{kkë¯ ‡Ã|>ïv»i“¦…„ÐÙ|o0d³YY–eY6!B¡!Æo2ÿ_Š¢d2™H$âr¹ªÕª>)IÒèR!˜J°F«Õj4Fc|2§Ói«"À¿¡P€14MkµZ£ÇÁ`Ðl6½^ïèC‹Ÿ££#³Ò€@ö?.ÊþF.—»¿¿ÿ4 ÿæhL5 %&ò ¦Ž×…÷g¡ IEND®B`‚opengv/doc/addons/images/triangulation_noncentral.eps0000664016516101651610000005623213344612246022115 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/triangulation_noncentral.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 12:08:05 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 679 471 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -25.759100 -21.049123 translate %%EndProlog 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 48.470700 14.294200 m 46.150000 4.700000 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 27.322700 12.500000 m 49.372700 5.175000 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.625000 16.225000 m 30.980637 17.726206 l s [] 0 sd 0 slj 0 slc n 31.322944 17.879343 m 30.764443 17.903365 l 30.980637 17.726206 l 30.968626 17.446956 l ef n 31.322944 17.879343 m 30.764443 17.903365 l 30.980637 17.726206 l 30.968626 17.446956 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.650000 16.225000 m 27.657316 19.842598 l s [] 0 sd 0 slj 0 slc n 27.658074 20.217597 m 27.407063 19.718103 l 27.657316 19.842598 l 27.907062 19.717092 l ef n 27.658074 20.217597 m 27.407063 19.718103 l 27.657316 19.842598 l 27.907062 19.717092 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.625000 16.225000 m 30.736892 13.868853 l s [] 0 sd 0 slj 0 slc n 31.035864 13.642489 m 30.788144 14.143623 l 30.736892 13.868853 l 30.486325 13.744993 l ef n 31.035864 13.642489 m 30.788144 14.143623 l 30.736892 13.868853 l 30.486325 13.744993 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 27.318200 12.516100 m 32.458797 10.779687 l s [] 0 sd 0 slj 0 slc n 32.814076 10.659679 m 32.420376 11.056542 l 32.458797 10.779687 l 32.260366 10.582837 l ef n 32.814076 10.659679 m 32.420376 11.056542 l 32.458797 10.779687 l 32.260366 10.582837 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 45.850000 17.500000 m 47.424821 20.518407 l s [] 0 sd 0 slj 0 slc n 47.598284 20.850877 m 47.145354 20.523226 l 47.424821 20.518407 l 47.588647 20.291943 l ef n 47.598284 20.850877 m 47.145354 20.523226 l 47.424821 20.518407 l 47.588647 20.291943 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.800000 17.500000 m 49.081575 15.548793 l s [] 0 sd 0 slj 0 slc n 49.403901 15.357140 m 49.101902 15.827562 l 49.081575 15.548793 l 48.846364 15.397794 l ef n 49.403901 15.357140 m 49.101902 15.827562 l 49.081575 15.548793 l 48.846364 15.397794 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.875000 17.500000 m 44.039660 15.181676 l s [] 0 sd 0 slj 0 slc n 43.806897 14.887659 m 44.313260 15.124506 l 44.039660 15.181676 l 43.921237 15.434858 l ef n 43.806897 14.887659 m 44.313260 15.124506 l 44.039660 15.181676 l 43.921237 15.434858 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 48.453600 14.287500 m 47.465005 10.106073 l s [] 0 sd 0 slj 0 slc n 47.378724 9.741134 m 47.737058 10.170199 l 47.465005 10.106073 l 47.250472 10.285240 l ef n 47.378724 9.741134 m 47.737058 10.170199 l 47.465005 10.106073 l 47.250472 10.285240 l cp s 0.000000 0.000000 0.000000 srgb n 46.247900 6.641120 0.187500 0.200000 0 360 ellipse f 0.100000 slw [] 0 sd [] 0 sd n 46.247900 6.641120 0.187500 0.200000 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.935400 6.316120 m 46.685400 7.041120 l s 1.000000 0.000000 0.000000 srgb gsave 30.968700 10.567000 translate 0.035278 -0.035278 scale start_ol 1024 5440 moveto 97 5440 lineto 97 5907 lineto 1024 6171 lineto 1024 6828 lineto 1024 7471 1195 7955 conicto 1366 8440 1685 8761 conicto 2004 9083 2467 9245 conicto 2931 9408 3516 9408 conicto 3661 9408 3815 9398 conicto 3970 9388 4118 9371 conicto 4266 9355 4391 9332 conicto 4516 9309 4608 9283 conicto 4608 7808 lineto 4190 7808 lineto 4002 8542 lineto 3943 8603 3842 8653 conicto 3742 8704 3593 8704 conicto 3450 8704 3330 8616 conicto 3210 8528 3125 8328 conicto 3041 8129 2992 7812 conicto 2944 7496 2944 7039 conicto 2944 6144 lineto 4160 6144 lineto 4160 5440 lineto 2944 5440 lineto 2944 576 lineto 3943 422 lineto 3943 0 lineto 358 0 lineto 358 422 lineto 1024 576 lineto 1024 5440 lineto end_ol grestore gsave 48.492500 12.207900 translate 0.035278 -0.035278 scale start_ol 1024 5440 moveto 97 5440 lineto 97 5907 lineto 1024 6171 lineto 1024 6828 lineto 1024 7471 1195 7955 conicto 1366 8440 1685 8761 conicto 2004 9083 2467 9245 conicto 2931 9408 3516 9408 conicto 3661 9408 3815 9398 conicto 3970 9388 4118 9371 conicto 4266 9355 4391 9332 conicto 4516 9309 4608 9283 conicto 4608 7808 lineto 4190 7808 lineto 4002 8542 lineto 3943 8603 3842 8653 conicto 3742 8704 3593 8704 conicto 3450 8704 3330 8616 conicto 3210 8528 3125 8328 conicto 3041 8129 2992 7812 conicto 2944 7496 2944 7039 conicto 2944 6144 lineto 4160 6144 lineto 4160 5440 lineto 2944 5440 lineto 2944 576 lineto 3943 422 lineto 3943 0 lineto 358 0 lineto 358 422 lineto 1024 576 lineto 1024 5440 lineto end_ol grestore gsave 49.081942 12.207900 translate 0.035278 -0.035278 scale start_ol 1024 8768 moveto 2688 8768 lineto 2185 5632 lineto 1514 5632 lineto 1024 8768 lineto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 43.075000 6.027500 translate 0.035278 -0.035278 scale start_ol 2693 5795 moveto 2836 5893 3009 5981 conicto 3182 6069 3387 6131 conicto 3593 6194 3840 6233 conicto 4088 6272 4388 6272 conicto 5667 6272 6289 5525 conicto 6912 4778 6912 3166 conicto 6912 2426 6745 1818 conicto 6579 1210 6233 778 conicto 5888 346 5360 109 conicto 4832 -128 4108 -128 conicto 3756 -128 3417 -85 conicto 3078 -43 2713 49 conicto 2719 -24 2729 -151 conicto 2739 -278 2742 -421 conicto 2746 -564 2749 -701 conicto 2752 -838 2752 -938 conicto 2752 -2304 lineto 3653 -2458 lineto 3653 -2880 lineto 165 -2880 lineto 165 -2458 lineto 832 -2304 lineto 832 5568 lineto 159 5722 lineto 159 6144 lineto 2680 6144 lineto 2693 5795 lineto 4992 3137 moveto 4992 3846 4901 4317 conicto 4810 4788 4654 5064 conicto 4499 5341 4294 5454 conicto 4090 5568 3862 5568 conicto 3531 5568 3248 5496 conicto 2966 5425 2752 5321 conicto 2752 713 lineto 3278 576 3849 576 conicto 4434 576 4713 1219 conicto 4992 1863 4992 3137 conicto end_ol grestore gsave 44.059076 6.027500 translate 0.035278 -0.035278 scale start_ol 6848 3584 moveto 6848 2624 lineto 640 2624 lineto 640 3584 lineto 6848 3584 lineto 6848 6272 moveto 6848 5312 lineto 640 5312 lineto 640 6272 lineto 6848 6272 lineto end_ol grestore gsave 45.065634 6.027500 translate 0.035278 -0.035278 scale start_ol 2941 -192 moveto 2711 -192 2510 -107 conicto 2310 -22 2165 125 conicto 2020 273 1938 470 conicto 1856 667 1856 896 conicto 1856 1119 1938 1319 conicto 2020 1519 2165 1666 conicto 2310 1814 2510 1899 conicto 2711 1984 2941 1984 conicto 3171 1984 3368 1899 conicto 3565 1814 3713 1666 conicto 3861 1519 3946 1319 conicto 4032 1119 4032 896 conicto 4032 667 3946 470 conicto 3861 273 3713 125 conicto 3565 -22 3368 -107 conicto 3171 -192 2941 -192 conicto 3264 2560 moveto 2560 2560 lineto 2188 4608 lineto 2809 4771 lineto 3058 4836 3280 4943 conicto 3502 5050 3669 5245 conicto 3836 5441 3934 5743 conicto 4032 6046 4032 6501 conicto 4032 6956 3953 7278 conicto 3875 7600 3707 7805 conicto 3540 8010 3284 8101 conicto 3028 8192 2668 8192 conicto 2353 8192 2113 8110 conicto 1874 8029 1690 7907 conicto 1408 6592 lineto 832 6592 lineto 832 8547 lineto 1339 8680 1849 8756 conicto 2359 8832 2964 8832 conicto 4445 8832 5198 8261 conicto 5952 7690 5952 6542 conicto 5952 6110 5834 5716 conicto 5717 5323 5474 5000 conicto 5232 4678 4866 4436 conicto 4500 4194 4009 4059 conicto 3440 3904 lineto 3264 2560 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slj 0 slc 0.000000 0.000000 1.000000 srgb n 44.487500 18.650000 m 39.662500 20.675000 32.812500 19.800000 29.304416 18.179176 c s [] 0 sd 0 slj 0 slc n 28.963994 18.021893 m 29.522745 18.004656 l 29.304416 18.179176 l 29.313034 18.458552 l ef n 28.963994 18.021893 m 29.522745 18.004656 l 29.304416 18.179176 l 29.313034 18.458552 l cp s gsave 36.150000 19.252500 translate 0.035278 -0.035278 scale start_ol 3392 3712 moveto 3392 640 lineto 4515 467 lineto 4515 0 lineto 306 0 lineto 306 467 lineto 1344 640 lineto 1344 8128 lineto 221 8296 lineto 221 8768 lineto 4411 8768 lineto 5510 8768 6248 8588 conicto 6987 8408 7432 8084 conicto 7877 7761 8066 7309 conicto 8256 6858 8256 6315 conicto 8256 5903 8164 5530 conicto 8072 5157 7865 4843 conicto 7659 4529 7321 4287 conicto 6983 4045 6484 3895 conicto 8855 640 lineto 9792 467 lineto 9792 0 lineto 6958 0 lineto 4412 3712 lineto 3392 3712 lineto 6208 6303 moveto 6208 6830 6103 7170 conicto 5998 7510 5768 7708 conicto 5538 7906 5177 7985 conicto 4816 8064 4311 8064 conicto 3392 8064 lineto 3392 4416 lineto 4344 4416 lineto 4862 4416 5220 4521 conicto 5578 4627 5798 4854 conicto 6018 5082 6113 5438 conicto 6208 5795 6208 6303 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.117647 0.878431 1.000000 srgb n 27.737500 16.200000 m 45.301860 17.416368 l s [] 0 sd 0 slj 0 slc n 45.675964 17.442276 m 45.159887 17.657135 l 45.301860 17.416368 l 45.194430 17.158330 l ef n 45.675964 17.442276 m 45.159887 17.657135 l 45.301860 17.416368 l 45.194430 17.158330 l cp s gsave 36.675000 16.477500 translate 0.035278 -0.035278 scale start_ol 2874 -128 moveto 2382 -128 2031 -11 conicto 1680 106 1457 311 conicto 1234 516 1129 799 conicto 1024 1082 1024 1414 conicto 1024 5440 lineto 221 5440 lineto 221 5880 lineto 1168 6144 lineto 1946 7552 lineto 2944 7552 lineto 2944 6144 lineto 4238 6144 lineto 4238 5440 lineto 2944 5440 lineto 2944 1552 lineto 2944 1131 3118 917 conicto 3293 704 3577 704 conicto 3796 704 4012 737 conicto 4229 770 4416 809 conicto 4416 232 lineto 4324 167 4147 101 conicto 3970 36 3756 -13 conicto 3543 -63 3310 -95 conicto 3078 -128 2874 -128 conicto end_ol grestore 0.000000 0.000000 0.000000 srgb gsave 25.759100 16.731800 translate 0.035278 -0.035278 scale start_ol 5010 4442 moveto 5010 4617 4729 4884 conicto 4449 5152 4449 5433 conicto 4449 5647 4582 5767 conicto 4716 5888 4943 5888 conicto 5250 5888 5470 5654 conicto 5691 5420 5691 5099 conicto 5691 4724 5457 4141 conicto 5223 3559 4876 3064 conicto 3847 1618 3019 681 conicto 2191 -256 1937 -256 conicto 1817 -256 1817 212 conicto 1817 788 1723 2013 conicto 1630 3238 1523 3934 conicto 1389 4858 1229 5125 conicto 1069 5393 681 5393 conicto 427 5393 281 5380 conicto 281 5554 lineto 748 5634 1095 5701 conicto 1443 5768 1576 5808 conicto 1710 5848 1817 5868 conicto 1924 5888 2031 5888 conicto 2244 5888 2464 4308 conicto 2685 2729 2765 922 conicto 3179 1350 lineto 3887 2100 4448 3043 conicto 5010 3987 5010 4442 conicto end_ol grestore gsave 26.490913 16.731800 translate 0.035278 -0.035278 scale start_ol 1189 5392 moveto 748 5392 lineto 721 5594 lineto 2779 5888 2805 5888 conicto 2872 5888 2872 5834 conicto 2445 4386 lineto 3032 5197 3553 5542 conicto 4074 5888 4729 5888 conicto 5437 5888 5851 5442 conicto 6265 4997 6265 4224 conicto 6265 2640 4989 1256 conicto 3714 -128 2258 -128 conicto 1817 -128 1376 123 conicto 882 -1752 882 -2149 conicto 882 -2560 1737 -2560 conicto 1737 -2752 lineto -1002 -2752 lineto -1002 -2547 lineto -828 -2547 -721 -2527 conicto -615 -2507 -508 -2446 conicto -401 -2386 -347 -2312 conicto -294 -2238 -214 -2071 conicto -134 -1904 -87 -1736 conicto -40 -1569 40 -1248 conicto 120 -927 193 -612 conicto 267 -297 400 218 conicto 534 734 668 1242 conicto 1616 4830 1616 5031 conicto 1616 5151 1469 5271 conicto 1323 5392 1189 5392 conicto 5063 4174 moveto 5063 5312 4181 5312 conicto 3687 5312 3186 4882 conicto 2685 4452 2431 3804 conicto 2137 3062 1850 2017 conicto 1563 973 1563 642 conicto 1563 429 1743 290 conicto 1924 152 2204 152 conicto 3006 152 3694 866 conicto 4382 1581 4722 2493 conicto 5063 3406 5063 4174 conicto end_ol grestore gsave 46.625000 18.442500 translate 0.035278 -0.035278 scale start_ol 5010 4442 moveto 5010 4617 4729 4884 conicto 4449 5152 4449 5433 conicto 4449 5647 4582 5767 conicto 4716 5888 4943 5888 conicto 5250 5888 5470 5654 conicto 5691 5420 5691 5099 conicto 5691 4724 5457 4141 conicto 5223 3559 4876 3064 conicto 3847 1618 3019 681 conicto 2191 -256 1937 -256 conicto 1817 -256 1817 212 conicto 1817 788 1723 2013 conicto 1630 3238 1523 3934 conicto 1389 4858 1229 5125 conicto 1069 5393 681 5393 conicto 427 5393 281 5380 conicto 281 5554 lineto 748 5634 1095 5701 conicto 1443 5768 1576 5808 conicto 1710 5848 1817 5868 conicto 1924 5888 2031 5888 conicto 2244 5888 2464 4308 conicto 2685 2729 2765 922 conicto 3179 1350 lineto 3887 2100 4448 3043 conicto 5010 3987 5010 4442 conicto end_ol grestore gsave 47.356813 18.442500 translate 0.035278 -0.035278 scale start_ol 1189 5392 moveto 748 5392 lineto 721 5594 lineto 2779 5888 2805 5888 conicto 2872 5888 2872 5834 conicto 2445 4386 lineto 3032 5197 3553 5542 conicto 4074 5888 4729 5888 conicto 5437 5888 5851 5442 conicto 6265 4997 6265 4224 conicto 6265 2640 4989 1256 conicto 3714 -128 2258 -128 conicto 1817 -128 1376 123 conicto 882 -1752 882 -2149 conicto 882 -2560 1737 -2560 conicto 1737 -2752 lineto -1002 -2752 lineto -1002 -2547 lineto -828 -2547 -721 -2527 conicto -615 -2507 -508 -2446 conicto -401 -2386 -347 -2312 conicto -294 -2238 -214 -2071 conicto -134 -1904 -87 -1736 conicto -40 -1569 40 -1248 conicto 120 -927 193 -612 conicto 267 -297 400 218 conicto 534 734 668 1242 conicto 1616 4830 1616 5031 conicto 1616 5151 1469 5271 conicto 1323 5392 1189 5392 conicto 5063 4174 moveto 5063 5312 4181 5312 conicto 3687 5312 3186 4882 conicto 2685 4452 2431 3804 conicto 2137 3062 1850 2017 conicto 1563 973 1563 642 conicto 1563 429 1743 290 conicto 1924 152 2204 152 conicto 3006 152 3694 866 conicto 4382 1581 4722 2493 conicto 5063 3406 5063 4174 conicto end_ol grestore gsave 48.240984 18.442500 translate 0.035278 -0.035278 scale start_ol 1763 5632 moveto 1937 7764 2044 8177 conicto 2324 8842 2792 8896 conicto 2966 8896 3093 8783 conicto 3220 8670 3220 8509 conicto 3220 8177 2044 5632 conicto 1763 5632 lineto end_ol grestore 0.000000 0.000000 1.000000 srgb gsave 37.500000 19.550000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore gsave 38.034500 19.550000 translate 0.035278 -0.035278 scale start_ol 1201 3840 moveto 1319 5303 1392 5586 conicto 1583 6043 1901 6080 conicto 2020 6080 2106 6002 conicto 2192 5924 2192 5815 conicto 2192 5586 1392 3840 conicto 1201 3840 lineto end_ol grestore gsave 37.475000 18.435000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore 0.117647 0.878431 1.000000 srgb gsave 37.450000 16.700000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore gsave 37.984500 16.700000 translate 0.035278 -0.035278 scale start_ol 1201 3840 moveto 1319 5303 1392 5586 conicto 1583 6043 1901 6080 conicto 2020 6080 2106 6002 conicto 2192 5924 2192 5815 conicto 2192 5586 1392 3840 conicto 1201 3840 lineto end_ol grestore gsave 37.400000 15.750000 translate 0.035278 -0.035278 scale start_ol 2866 3840 moveto 2320 3840 1892 3401 conicto 1465 2962 1260 2375 conicto 1055 1789 1055 1245 conicto 1055 755 1273 473 conicto 1492 192 1883 192 conicto 2220 192 2515 363 conicto 2811 534 3184 940 conicto 3330 848 lineto 2920 329 2520 100 conicto 2120 -128 1610 -128 conicto 973 -128 623 236 conicto 273 600 273 1253 conicto 273 2329 1082 3180 conicto 1892 4032 2911 4032 conicto 3320 4032 3593 3819 conicto 3866 3607 3866 3285 conicto 3866 3110 3739 2985 conicto 3612 2861 3430 2861 conicto 3075 2861 3075 3212 conicto 3075 3305 3143 3457 conicto 3211 3609 3211 3655 conicto 3211 3840 2866 3840 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.627451 0.125490 0.941176 srgb n 27.665600 16.195700 m 27.350361 12.907781 l s [] 0 sd 0 slj 0 slc n 27.314571 12.534493 m 27.611150 13.008351 l 27.350361 12.907781 l 27.113432 13.056071 l ef n 27.314571 12.534493 m 27.611150 13.008351 l 27.350361 12.907781 l 27.113432 13.056071 l cp s gsave 26.153400 14.466900 translate 0.035278 -0.035278 scale start_ol 6272 5594 moveto 3804 -128 lineto 3021 -128 lineto 448 5568 lineto 0 5722 lineto 0 6144 lineto 3152 6144 lineto 3152 5721 lineto 2420 5555 lineto 4000 2041 lineto 5429 5568 lineto 4711 5722 lineto 4711 6144 lineto 6720 6144 lineto 6720 5722 lineto 6272 5594 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc n 45.847000 17.447400 m 48.138831 14.632694 l s [] 0 sd 0 slj 0 slc n 48.375607 14.341899 m 48.253770 14.887477 l 48.138831 14.632694 l 47.866042 14.571776 l ef n 48.375607 14.341899 m 48.253770 14.887477 l 48.138831 14.632694 l 47.866042 14.571776 l cp s gsave 46.294800 15.333200 translate 0.035278 -0.035278 scale start_ol 6272 5594 moveto 3804 -128 lineto 3021 -128 lineto 448 5568 lineto 0 5722 lineto 0 6144 lineto 3152 6144 lineto 3152 5721 lineto 2420 5555 lineto 4000 2041 lineto 5429 5568 lineto 4711 5722 lineto 4711 6144 lineto 6720 6144 lineto 6720 5722 lineto 6272 5594 lineto end_ol grestore gsave 47.178971 15.333200 translate 0.035278 -0.035278 scale start_ol 1024 8768 moveto 2688 8768 lineto 2185 5632 lineto 1514 5632 lineto 1024 8768 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 27.319053 12.479749 m 26.561598 13.239477 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 26.658642 12.788058 m 26.482660 13.318652 l 27.012724 13.141081 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.335526 12.470830 m 26.770651 11.520562 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 27.183909 11.726510 m 26.713523 11.424456 l 26.754111 11.981998 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 27.342182 12.479232 m 28.295296 12.902483 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 27.839045 12.973417 m 28.397477 12.947859 l 28.041972 12.516448 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 48.452077 14.280512 m 49.405191 14.703763 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 48.948940 14.774696 m 49.507373 14.749138 l 49.151867 14.317727 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 48.445767 14.271842 m 49.062334 13.326015 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 49.059772 13.787740 m 49.123390 13.232354 l 48.640911 13.514692 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 48.437506 14.297874 m 47.447121 13.800680 l s 0.100000 slw [] 0 sd 0 slj 0 slc n 47.906218 13.751421 m 47.347202 13.750518 l 47.681889 14.198273 l s showpage opengv/doc/addons/images/absolute_central.png0000664016516101651610000011262213344612246020331 0ustar dimadima‰PNG  IHDRIʘ.HˆbKGDÿÿÿ ½§“ IDATxœìÝw\SWð_{È¢ˆî ­Z÷nݵ¨uÔQ­uWE­£Ö=먶öµU[à­¸q {†Üçý#(¨€Œ$7óýðG¸Ü{Î#Άa¦ òÃ0 èËm £»þúë¯ääd¾£`ý#`}’ £³ú÷”tîÜ9ccc¾ca}ÂÚm £»FÅqß±0Œ>a¹atTDDDDD€ÿýï“&Mâ;†Ñ',·1ŒŽºwïÞ»×»víZ¿~=Á0Œ~a¹atÔ;wò~:{öìýû÷ó Ãè–ÛFGæý”ˆ¼¼¼|}}ùЇaô›'É0:ÊÞÞ>>>þƒ‹Mš4á%$†Ñ¬ÝÆ0º(<<üãÄ 55µÿþ‘‘‘Ú‰aôËm £‹îÞ½[ЗBCC?ÿüó””mÆÃ0ú…å6†ÑE ¶°µµ}÷úÁƒ”ËåÚ ŠaôËm £‹Þå6¡P8tèP;vLHHðóó[³fÍðáÃCCCÇŒÃÖt3L¾Ø\†ÑEª‰$FFFû÷ïoݺµ³³³••U||¼H$zwORR’¡¡¡™™q2Œnbí6†Ñ9‰$>>¾B… gΜ6lXõêÕ]]]“““?訴¶¶f‰aòÅrÃèœÀÀÀÊ•+tîÜYu¥[·nüüüx‹aôËm £sÒÓÓoܸѨQ£wW<==ÁrÃoc=œœloo/ ÌÍÍù‡atk·1Œ°²²jÞ¼¹\.à;†Ñ,·1Œ~`Cn St,·1Œ~`¹aŠŽ·1Œ~P(¶¶¶)))oÞ¼©R¥ ßá0ŒNcí6†Ñb±ØÃÃÀ… øŽ…atËm £7ØJ†)"Ö'É0zãéÓ§ 4pttŒŒŒ|‡Ã0º‹µÛFoÔ¯_¿jÕªÑÑÑOž<á;†Ñi,·1Œ>éÚµ+X·$Ã| Ëm £OT+üýýù„atoc}S©R%SSÓ„„###¾ÃaÅÚm £O*V¬èææ–žž~óæM¾caÝÅrÃèÕJÖ-É0…`¹aô Û|‹a>‰·1ŒžÉÈȰ±±Q(±±±666|‡Ã0ºˆµÛFϘšš¶mÛV©T^ºt‰ïXFG±ÜÆ0ú‡uK2LáXncýæ“0LáØxÃè¥Réàà˜˜R£F ¾ÃaÃÚm £D"Q—.]Àšn S–ÛF/±!7†)ë“d½$‘HjÔ¨akk+²?Ræ=ì-Á0zÉÙÙÙÅÅ%!!áþýû|ÇÂ0:‡å6†ÑW¬[’a ÂrÃè+ÕJ–Ûæcl¼aôUrr²H$JLL433ã;†Ñ!¬ÝÆ0úÊÊÊÊÝÝ].—_½z•ïXF·°ÜÆ0zŒÃÍ0ùb¹aô›NÂ0ùbãm £Çär¹­­mzzzdd¤££#ßá0Œ®`í6†Ñc†††Dtá¾caÂrÃè·’ •J׬YÓ·o_//¯/¿ü²GOŸ>ÕL€ ÃÖ'É0ú-((ÈÍÍ­J•*oÞ¼)â#'Ožœ0aÂØ±c—.]jdd”žžnkkkgg*‰4-Ãhk·1Œ~kРA¥J•"""ž?^”û·oß>`À€Ñ£Gûøø¸~ýºL&‹ˆˆˆ‹‹Óp° £%,·1Œ~Eß äôéÓS¦LiÙ²åªU«Þ]lѢŤI“vïÞÍf£0eë“d½wðàÁÑ£G÷íÛ÷ĉ…Ü–ššZ«V­ØØX___Õâ†)«X»aô^·nÝÁÅ‹³³³ ¹í—_~‰uqqa‰)óXnc½çèèØ AƒÔÔÔÛ·orÛü·Ë½¦lc¹aÊ‚O¹Éd²Ghذ¡öÂbž°ÜÆ0eÁ'7–ŒU½°··×RL Öۦ,èØ±£‘‘Ñ­[·¤Ri¾7˜ššª^ÄÇÇð¥ÄÄÄ¢¯c½ÀrÔfff­[·V(—/_Î÷[[Û:uê8yòdÞë‘‘‘“&M266ÖF” £-,·1LñÉ3V¬X!Î;7{öìW¯^…„„lÞ¼yܸqëÖ­³³³Ób¤ £ql}Ô·oßnÕªUݺuŸ={VÐ=§OŸ^µjÕ½{÷D"‘««ëÈ‘#'Ož¬Ú„aÊ–Û¦ŒP*•‰‰‰aaaÕªUã;†áë“d˜2B$uêÔ ìn†a¹aÊv 7è°>I†);‚ƒƒkÕªegg#²¿\™ò‹ýô3LÙáââR³fÍøøxÕ$ Sn±ÜÆ0eJÉŽáf˜2†å6†)SØÀ·1L“˜˜hooohh˜˜˜hbbÂw8 ÃÖn+ߤR¤¥ñ£6©aawV¯®em•uýúu¾ÃaÞ°ÜV^¥¤`ÞLŸŽnÝðô)¬]‹‰sÊÙ±óæA"€S§°s'"#àáCøû#>^&“¥„„ $dê¨Q•*Uz !%ÅPi€8uìX»ü"E‚RßB†Ñ),·•'‡;áâ‚qãܼ‰ãÇ!ðÙ§äÍ=/^àîÝœ®Ô‹ñçŸ9mC‡°z5""`ÍLœˆà`X¸C‡âÅ ?Í›ãáCèÑ66PTݳ'llrr—š7ÏÉI³f¡[7<~ ëÖaâD¼| ¿ÿŽÕ«srÏ•+øóODEÀë׸{‰‰€œ6™j—ý¬,¨Q5kæ|ÏÛ¶…§'T§Ï Œ `ccÆÀÛ+ÀüùرÎÎYYY·GŽÜ=lX—É“ÍÍÍë¹{<dg/VëŒ2€V¿@p ¨êâ£ÄOÉh¹ xž­‰ÿ†ÑUÄ”GRÆ@nnäç§ÎÂ#"(8˜23‰ˆÉωˆNž¤;(2’ˆhûvòö¦"¢µkiÂzù’ˆhæLòô¤‡‰ˆ†§š5éÖ-""èÒ%"¢Ž  Ë—s_«®wêD]¼øáëÎ   r¯«^«®Ÿ?ÿáë~ýÈÚ:§üI“ÈÝnß&"š=›<=éÞ="¢õëiÂzöŒˆèÈòñ!‰„ˆèÒ%:z”bbˆˆ^¼ À@JI!"ŠŒ¤à`ÊÈ(Í÷5++ËÏÏÏÛÛÛÝÝ],¿{Ûzzx¬jÚôŠP˜ÄA"Yb1[\]ô÷µ“„jHÈYBNr’ÐðhòÍ eib=Ár[9ðèõî“ÕììhêT:|8çwñ?ÿÐŽAD´s'y{Óÿ-]JC†ÐãÇDïÿ®ïÛ—¬­) €ˆ¨KÈßÿÃ×]»“;ó¾öôÌÿu·n¯/Q÷î¾>{–ˆhÐ ²¶ÎÉOS¦»;ݸADôã4d=x@D´{7y{Ó‹DD§NÑŽNDtù2=JÑÑDD/_R` I¥DD©©”˜Hr¹f¾é%'—Ëýüü/^ìééùî@Qb±¸]»vÞÞÞ~§NI½½å††‘7cFXõêÄ…)óGް`ñâZ¡T]BNêA-Ãs2\ópZŸD‰,Å1eËmeZx8EBaNb8¤RêÑ#7g|ötæ å\Ïûúôi"¢ž=óÝ«ôï¿DD_}E5kæ´™¾ÿž<=éæM"¢M›h„œùçŸäã““;OŸ¦;(4”ˆèþ}òó£¸8"¢¨( ¦ôt-}t†R© ôñññôô477—Ï»»»···ŸŸ_JJ q÷ë¯T­šê?ô(ð*U"€ªV ëÓ‡‰‹Ë˜1cìÚµ«9I¨q9Ièû:˜B]"r2\ý0ZšHÙ|ÿÃFCØú¶2M.Ï…RY[cæL(•xúÞÞpwÇ–-xô“'£qc;†ÿþàA¨U ×®!2íÚ¡re#9..°²BZ²³an¾ÿmzˆîÝ»çïïïïïëÖ­ÔÔTÕu@ЬY3OOÏvíÚµnÝÚÞÞ>ç›7Ó½¼Ì‚‚ qã§^^)5j8ŒU311ÆÜ¼b@<<–Æ]¹Ò}É’óçÏŸ9sæA«ÛR0Ôÿ¤#“°Ü£-ðX޽)8™Ž6Æ8T±H¡îÝ‹/¾[,Ç输+£W®ävKÒ¨Qôô)ß1é‰jt­Ô7nÜ8dȇ¼ïÄš5kN˜0áèѣѪîÓ¼"#¹‘#I ˜_¥Š2;[CÍšafyëÖoNN(==‰¨N:=zä—ANM§Ò©º„jJèJfN‘Árz"+RÀÑÑ´kÑÇ짆Ñ,·•'wïÒ¨Q$@B!õîMW¯ò“~8|øðàÁƒKüxHHÈŽ;† âèè˜7ŸU¯^]•Ï"TCžËÌT.\˜3´flL‹ïÞ¸Q*•¾¾~ý•ꢛEG_=v, à€¬«W‰ÈÌÌ @bb¢TIΪJY­K"' ¹…Qp‰Fe2jØLLr&ß0ŒŽc¹­ü¹{—† ËÉpuëFQQ|ǤÓ~þùg‘H´lÙ²b=ªÊg•*UʛϪV­:jÔ¨;vö<ÇÑþýy‡Öþ^»6çKoÞÄÚÚðÊÌŒSÍ úî;¢Ü݉()) €¹¹¹êÞîä$¡ÛYÄM‹#' µC ÅŸH’–F^^äâBiiD”3Å•atËmåUT-^L*‹ )|G££ ÅôéÓU9éܹsŸ¼?..îèÑ£&L¨Y³fÞ|fkk;dÈOç³w®_O{·`£I“Û·û«æ Åß¹C5j^¥JbH=?ž32"€îÞ%¢Ç¨]»¶êþÈIB[’‰ˆ29êENMr®$ßäd"¢}ûH,¦U«JRÃhËmå[t4ë–,Hrr²jO}B¡0Eµjí# ùæ3+++U> R*‹ÜP U ¨Z‹f;8dËr‡ÅžýóO¸jÖkÛ¶ª<“}ÀÚš€äÎU÷œ9s@—.]TŸžH#' ‰É)!FA­ÂÉIBsâKò=QY¼˜D"úýw"¢¬¬’—Ã0š#SžU¬˜³ù󾘘˜¾}ûÞVíZÔ©SÇÂÂâÝW¥R©¯¯ïÕ«W¯]»öàÁ¥2gW+KKKöíÛ{zz6iÒD$£ÊÌLòñQ¬ZeMFF‚yó®Õ¬¹hÀ±¡aÎ OŸÖ=ÚˆãÚÙÕ?uÊ BÒ'O†K¥`¾aƒê®ˆˆU«VU}ÚÜ¢ßn»å Â ŽÆi¨oˆ±(%Kðå—¨]éépwÇ!X´ˆÍœet Ëm ó¡{÷îõéÓ'Rµ…# mÛ¶™™™×®]SMÙϛό;wîìéééééÙ¸qã¼»‡8€ bà ^¶ì‹¹så¹åÁÁƒ¾ûÎ())¹eËzçÎXY©®ÛîÜ ŽËî×Ï qcÕ•7oÞ On«,Æ*¨œ'¨†Ø`‡oâ°,Nbt)ÑÌþÚµàÜ9¼z…þÁÂ…%)„a4‡å6†yÏ©S§†žöþÑ?·nÝrppxwQ(6iÒ¤sçÎ]ºtñðð°´´,y}ׯgLœhªZµÖ´iäìÙ.ÎÎmÛ¶Í{˃]»œ'N)z÷¶:v o[r­[×oûv‘Ph°rå»›Uí¶*Uª¼»Rù£wyS̰ÂúdL‹Ç_ލSÒ&×À¸pÖÖ04ÄŽHKÃÌ™²Mj]Àw§(Ãè¾ë|ŸAΖW~~iªÉ‚¥$‘äZ›ik›‘o±7np*p¿V-.ÏØ[vvöass$mÛæ½½gÏžNœ8QxåÑ·qä$¡vo(¾Ôs‰bbÈÌ,wÛ5†áËm CDÄqÜÒ¥K‰`ddä«ÚåR-RSÉÛ[n`@gdD‹Ÿ8|8ß¹*W–-S˜˜9l˜òƒ­/ƒƒ9±X)*Ÿ?Ï{ÙÍÍ @``à'£Èâ¨_9IhpT §Mæuò$͘AD”œL¿þJ\© d˜Ò`¹a(33sĈ…÷pTªTI [“p÷ë¯\åÊpÀ`÷âÅÝûbË–t€€”!Cèý™–YYY™Ã‡@£Gð” €|67ÉO¬‚Z¿!' Í.Å´ÉŒGÍ™£¶¦Xnc’Éd×®][½zõ€*W®\Pz«_¿~RRRÉ«¹z5½AƒœUkmÚDŸ8qAu²A¾Nœ ##n¶jõq#hß¼y @)åì=ýVzzºª•ɹÝôDFuCÉIB;¥ÅüçààAªT)ç<ÕéF £},·1̇ÂÃÃ;6wîÜŽ;æÝ•@çÎe²¢íØ—D"ïß_5´&L¶·O.4Gþ>lX¶jÛ¬YùöîÝ®]›€ðÏ>ûàú‹/8;;+º³éä,!g ù•ê°¹\ªEo‘©iAÿ†Ñ,–Û¦0 …âÑ£G»wïöòòjÔ¨‘H$=ztÑ[Ey‡Ö”FF´xqÀ™3…X¿q£ tܸüïxú”D"ÎÀ€>ê#½pá€öíÛ5¼·6'““„ê…Ñ3õg·oÐĉj+aŠŽå6†)Õªí°°°OߪTrÛ·çZÛúý÷Ÿ|(sûvÕVŸ· *(€ûuêoÒ8pà€áÇ:¼Ì'' µUÇ´ÉwnÝ¢ÔT"¢áÃiãFÖ€c´‡å6†Ñ€+W2ßmÙ¦MŠ¿ÿ ÕAáS*•GÚ·çT¼Ûù#;&Oæ¹PHùåו+W˜={v B–s44šœ$40ŠdjMBW¯@––ôæ:‹e˜B°e– £V‰¼xx½ 'Z[Ç?nѵkëÖ­ .û§Ÿ†]½JÀÓiÓ0{vA· ùRÄ€jÕ>þêÇ ·‹Î@€mö¨.F  óJP@ڵÉØ»Uªàñc\¹¢ÎÂ&_,·1Œš¤¦bÞ­ÎÂæc,·1L©q·};W»6V¯+Mß|oïöÝ»0Íòc …â¯Fœví"‘‡Õ^³¦ ;ccc¯õè"ÎË ïŸ ÷Î%—€«6ÛA¬N‚oF‰‹ÉŸ±1 BýúèÔ ¤R5—Ï0ï°ÜÆ0¥sõª¬qcá7ߣ£Ñ¶­üÊ•wïÎ\·®ˆO‹øaè³gÙ€dåJ|ñE!w>Úµ«Gv¶L$Ο_Ð=l”\2Làm ˜gòÒ”ô!±+Vàöm˜šbß>Ô©ƒ3gÔY>üÃrÔÔë×Yݺ¡C£  7"Ñ{ûð#G ÛµkÖ¬YQžÎHOØ¡V¯†±qâž=5æÎ-ü~Ïk×dŒWбDr¹<66V$U* UWt-ñ¥9Ò ãã¯üôýÅbdÿûbb¢ÖžO†y‡å6†)>ÕÐZ:Æþþ ccøø$]»¶.,¬š“SQKà¸Ëõë7¾z5[,ÆßWüê«Âo÷[´gÎÀÂÂÚǧ {¢¢¢8Ž«X±bIÎÙùÈr´1F„^qQéËûÐÉ“øë/ ©_~‰ˆõWÁ”g,·1Lq(•´c‡ÒÕ«W‹ŠÀ://x{»µjell\ÔB ŒÝ3,,C$Jøí7ôèQøí¡¡¡¢+¤[Û‚nSK‡ä;b¶ÙÃYŒ{2ÌŠ‡Ú³›H„`Á9‚Ñ£Õ]S¾±óۦȮ\‘O™bøø± ¶m¹uëÜ ÜÝÝ‹UFô›7/Z¶ìKKãÿ5íÐá“Txð  Çeš/]ZÈmêÍm¬…Øã€Ñø7õ¤˜ZA]¿gñb„†B5‡æÁ4jÄN€cÔ€ý1L¼~Þ¥ << ?~#ckûß¾}¢Ö­‹›ØÖ®]Ǩ¨TCC\¸ ,BbS*•V?ýÀtþ|¼=n;_¥\¯ZØl1ðS2þIWcÁ¹ìíñÏ?¨W¢m[ôî ¹Z'°0åËm S¨”LŸ®tu5»x1ÛØ>>)7nüêZ»vqK’I¥èß¿eXXŠ‘Qö™3(Z^\ÿùç¸z•³²ÂÌ™…ßYš…Û…èh‚ùÖ `vj2ëÄÇÃÔ5j €Óa¦XŸ$Ã@©ävíâ-ÇÅ ‚]Aâ„ ÞÞÞõKTØÓÛ·¥md2T®léïzõŠòTbb¢‡¿?€äqãl*|¢O°ô‹Û òµ%^+p(^±8Y Ž"µ×]»âÁØÛÀ„ hßž Â1%' ÒÀ(†ÑwÙS§<~ €kÛV°qãKKË:uê”°´ÔÔðFªI$qFFv Š^ιsèÑ#ËÂÂ82ŸZÞ®]»ëׯ_ºt©cÇŽ%Œ³` ¨X\Ï‚›!þt„Iþç“«G@:v„¹9^¼@Á§é1LaXŸ$ü/$$£kWtìhðøq¤¡á´ŠŸíØ!hѢĉ-ôÑ#êÑ£šD"µµ5½w¯è‰íù³giÓ§0þþûO&6h`.I^ªi“5Äx,×ȴɼ<cÇÂÛÛÞÉÉPk†¯]›Ñª• ,LÙ±cõ—/…î$’?Ž›)•0X´EíÓÐÂ킈ö¨m€'rÌŒ§ù[´ÀÂ…à8Œ‰öíqê”æ«dôËmLyrö,× pÖ,±T*kÕJpçN¯ðð%;v¨«øçþÙfî\Ó„„ŒöíE§O Š0qÿc¯–/½x5L§O/úSš[¸]s!ö8ÀFˆ³ج¥J9ŽŽ00@Zª‘ÑS,·1åCppz—.èÙSøâEŒ™ÙGLJ›6¡Y³Êê[ÌÝ¿_wÊ”Š@°››éùó05-A!þgÏbɘ?EPË}’*Nbl·‡¿Hq\óÓ&ˆÅر÷ï£~}>ص FF†‹‹–êeôËmLuæ Íš%xþ@F‹¦Û·G::ª±R…ˆ¤ÇŽY‹ôôNjúû—8±ÑÁNF NMoÛ½z ž?·´œR­ZÐæÍêZSÉÎÎ^ݵ«ñСHOÇ´i5/\(y‹ øçرN²½½‹[_’_ìPÇOµ5m2¯de!-M»µ2ºå6¦ I'Ǭ IDATNÆôé\£Ff7nd`ãF‰äçõ­å:~|öåËÆDC‡âçŸQº®ÎžQQN€´reƒâŸìÂËD’˜ ±Ç¶"œËÀOÚš6©²y3._ÆÈ‘HMźuP*µZ;£›XncÊ…‚Û°!ÛÉ ›6 í††ËÆŒQNjfm-«üG&“Ýûþ{ƒ#ÄååUå?J™Ø¢BB ||TX¿¾?í/ÈW51vØÃP€-Rü®ÝV”êó‘#1{6fÍÒjÕŒnb¹Ñ§OSÆÂY³ RS¥mÚàÑ£á11>»v‰JÑCX¥R¹¥eËÆ«V!;>>•vî,}{Û¶Ed¤¼^= úÉûwíÚuìØ±¼Wt$·ha„•6ðC"nfi»vooÔ«—s>9§åŽQFÇ°ÜÆè³'OÒÛ¶ÅçŸ ^¼H°²šT¹ò£Õ«Q¿¾U v)2Ñþý3?±³gÃÛ»ô†yÅÇ-]Z”ö_ç· 2f̘øøxÕ•|ÇÛâãヂ‚J^q 1‡—%² ßÄ!TûM~ m[ÁÙwî Q#<®ÕÚÂr£Ÿâã1q"׸±Ùéb±jhmÓë×TSš‘ššzºG|ýµ@ H]³ÆAMK«\/\pP*³ÜÜDƒåþZµjµk×îÀõë×ÿí·ßð~nS(ÿþûïàÁƒ4h`kk«–‹ë{kxš ‘ÃøX¤j·ý$À?âÉl߮ժÝB £_²³³úIfnN‰D{ÌÍ玟••¥…šwÕ«Çœ@@;wª«Ìcû÷gYX@'N#’%6–&LàÄbRD"nÆ쌌lU“pÜ977dB!ýó –ËåÊeË JðøÙ³g zSûøø¨1ÎRú_9I¨f(]×VûÁÁDDññ´hií§†áËmŒ“É+VÈÌÌ ±ø× æM˜‘‘¡µúS’“iÒ$äbq꟪·ð­+W¦ˆDŸ_ W*•NNN'¶¶mÛ*•Jõ†ZJ«ÉIBÃè5©¥[7hæLÞ`´Œå6FWýóÏ»¡µÈ¦MéÙ3í ­Ñ[·@ææté’ÚËß]­ñ –¸„ï¿ÿþƒÄfhhøèÑ#5©J¢¯cÉIB#HÊSÚ ¤Ö­)2’ˆHÇR?C±±± …š§±ñ6F÷¥´j…>}ðâERåÊ_U«ötíZÔ­«…¡µ\ …õÔ©£d² ±˜NŸFÇŽj.?1q|J ÛmÛJ\ÆØ±c?T›;w®››[icS7!°Ñõ œ©ñÐîš·îî¸q•*Áß#<œ ˜,Z´HµšEÔ›*¦TTCk"‰"‘|ófEf¦\.×rw®_W H€ÌÂBvýºÚËONN¾Û«Ô¥K)‹jѢŻ÷²«««6;l‹+ZA-ÃÉIBKù›6ID;@?üÀg L^ÆÆÆõêÕSoÓå6F7ÈdÙ?þ˜ejªZ;âà°lÆŒôôtírñÌ™3ªa0;;ºwOU¬3' €®]+eQÛÞ6û„Bá7Ôžæ<”QPr’ÐÁÞbHJ¢%KH¡ ޣםy ƒygÚ´iªŸáÇ«±X–Ûpô(Õ®­Z{Ý ={¦öÎ÷¢ÊÈH÷ð ÙÌŒ{òDC•¼0€€„-J_T||¼¡¡!€ &”¾4-ø7ªK¨f(]åiÚ¤ ÇÑØ±dnNçÏó£j´©r›z›nl¼áÕãÇi­[cèP¼|™êä4±fÍÐ-[P·®†¶9.Ü©ßOïÐÁ4 @áèhq玠~}TSÛ×ÍÖ­¥/ÌÖÖ¶OŸ>•+W^³fMéKÓ‚ÏM1µ„ÉqxÍËÈ@©„T ™ YZßЙÉëÇÌÊÊ ‹Ÿ={¦ÆQ7vî6ÓØX,\H{ö”ÊD¡ÐtÃão¾Q …¼d5WOŸöîÝ–HY½ºèÒ%8;k¢–¸¸¸ÓõêIH@ïÞøçµ”yúôi@гgOµ”¦L‹Ç?é¨i€ãލÀÓØ nÝB»vˆŠÂÝ»èÝ›Ÿ0Ê3‰DR»vm"R(666‰‰‰µjÕzöì™zÎ¥RWaŠ*++whÍÐðPÕª ¾ùF*•òR|<׬Ivvª¹z¶/\˜ pݽ«®2yß[«29êINMü.§NK#77‹‹µ'£ß|ó €Áƒ¨Zµjݺuìß¿_-…³ÜÆh×Ñ£äêªZ{U·.=ÎÛÐÚ[[–,‰©\™jЀ¢¢4[Ù·ß -õôÈ2 ZA­ÂÉIB xŽÄLJ4 øxžÃ(o^¿~m`` ‹¯\¹¢Êm‡P«V-µì:Är£-J[´Peµôš5¿qu=¯ãøÏΟY»6ÅÄh´®«GŽ‘ …ôø±F+ÒßN›ÜÏß´I•”"¢S§hëVž#)?T¶Ñ£G‡‡‡«r›B¡PcÓå6FóbbhÔ( ˆ¤k×êȾ~²à`ÕüÌØ5(Q³«®ÂÂÂvˆDd ÑŠôË)Õ´I ]áuÚ$½yC&&$ÐŋګtÁÕ{ù|dnN•+SÇŽ4kh/*•7ohî\êÜ™œÉÒ’Äb²¶¦-ÈÛ[ k'Þ5Ú^½zõ.·‘›n,·1š¤Z31Q ­¯[wù¬Y©©©|‡EJ¥ò‡/¾ˆRm©Õ¦ %'kºÆ§§Ne œ@@[Z §Ö'‘“„ê‡Ñ m¯ÑÿÐÞ½4cisø2%…®]£uëÞËjÝ»Óøñ4v,õïOU«æ^÷ð ðpíÅæç§z×ÒàÁ´p!MšD¶¶9‘S)wW}×h#¢¼¹MM7–ÛÉ3´T£½xÁw@¹â®_‰HjÖŒÒÒ´Qå×_ 6LuéŽhZ9I¨ýJЕJ;–æÎÕ^ááïå¶¼§M(•4o^î—j×&­mªªÊmy”ˆˆÈMo¦¦ôæMÉ Ÿ2eб±ñÓ§OéýÜFD¿þú«µµõöíÛK=ËmŒFÈmÙÙÙÍšÞ»wo¾³ýä×ϯŽe óNL æÌÁo¿™s\œ@ \±ÂvΜ­jY­¢r¹ü‡>}æúûƒãЯŸÍÀÈHÓ•J$’š¿ý&$J4ÈÜÕUÓÕé#cvÚ£_4nËð}"ÖÚòLóæøãXXÀÅ))°´ä3b1ÜÜpéRΧ·naÔ(mÔ[¹2ÆŽEóæï]tqÉ}Rªò­­­ó½.‹- ø¦_¼xÑÂÂÂÕÕÕÀÀ@uE*•Êd²Ý»w|3Û—„Q™Lþý÷r''<ƒÓnn›&OOž IlÄwï.¾xÑŽã;uÂÑ£ZHlœ³²F œHd¾zµªÓS"춇©GÓ°7•ç`D·nHи1&Nïû[æ¾V*KXÈÔ©>ýÑ£GÎýõëcß¾ß"Š<[ÉhóX•°°°ÐÐлwïÞ¼yóæÍ›×¯_wuu=vì˜ÍÇ7³ÜƨߢaCÃU« åò;ÎÎxô¨×£GË7o®P¡ß‘åÈÈÈð]²Dس§Yv¶´o_ÿ÷~ahLDD„|Ñ"Ç ÇŽ}ï^æ# ±ÁBàÇDœÏä;àåKDF"0éé‘R©‘-•?Èm={ÒĉԧOž>-m-))õé÷çINÎ ã?4Ò_ÜÜöí·ß^¸pá“·±ÜÆä'1‘TÛoØ{ñþýä¦MU?æÙõëÏlÜ8@û™R©¤ýûI$" M뉈¦¶jÅrŠŒÔ~íeÀSÕ %' íäõˆˆ¼¾úŠZ»VÍÅæÛ'©PP³fïmJRÊ.ÿ)S>Ý:è³Ïòy¶F ()©T¤X¹í·ß~[³fMQîdó$™üÌžÈHxxàÛo :£GÃݽÂýû1À«~?~¼þÁƒ:ðhþ‚‚‚æW¬HãÆA©ÄêÕfË–i?†å††@ùõרTIûµ—õ ±Å"`eüt`Ú$€®]acóá’/ ‰°c„oC`ãFmÔ›¯¦Mac++ÞPyúôé¹sçæÌ™S¤»K—q™²èÔ)ÈÌŒ‚ƒ)3S6¾ÌÀ@5´v¥k×Ó§ó|ÖZüÏÃS“ÆÓ¾îR_ßœݸ8^(3¶¼6ùTM³òJIõ³Iÿ­¶2 ™'9mZîucc5ôL–ŒR©ÁÉÅEl·¥¦¦öîÝ;%¥¨gF°ÜƼï]oäºu´?U«¦zc·µ¥W¯øîÓ¢££iýz8 sÓ&^bð÷÷÷‰Ðꦄe×Üxr’P™6™šJ..$}8Y¿Ä ÉmRiÎÛQõÑ¢Gh„†ÒˆÔ¹3ýö›FÊ/bn6l˜@ èܹó}Õàç§°ÜÆ¼ǫI“”úõUï'¥›ÛÂöíoß¾ÍwdŸæëëû£jö¦X¬©7bìûê+dFFì¼KµÈæhh49Ih€nL›$¢_~¡.]Ô¶ÉváëÛþüó½¯.[–!r9­]KK—Ò¶mÔ«WaËÔŠëíúUèÆ µûNQrÛ¦M›Þõ5={VuýìÙ³žžžaaa?Âr“Ç_å$‘ˆ€Dàñ×_“\ÖÐÍË P…Ü‘#|ÆÑµ+rÖhSŸD%uxCNš©3]¼YYDDÿMþþ¥-ªðÜFD½zå~ÕÀ€îÝûð†Œ êÒ…vì "JL$€N*mT*©©ïŶb…zŠÍ듹ã¸#Gޤ¦¦ž?^5ÆokkED ,ð×_}üËmÌ[ÉÉ\ÕªÈ--I,Žru½ãîž=b HžžÔ¼9Õ©CK–ðeþ.^¼˜9u*J¥&¦i ÇqÇ'€¬¬45«¬¼z)§aä$¡­:3Ú{û6‰Åù,“)ºŒ ºv||ÞË'ÒÙ³•{Ûë×djš{CýútäÈ{gFM˜@=zä~úø±:WÂU¯ž[õÉ“j+öâ®ؽ{·µµu÷îÝ333Ïœ9ãèè˜ðñm,·1o©&8þ¡“ûkœ;sf§j|ËÄ„NŸæ1’ãÇ_à-â1Œ²êbÕ³„Îiã`¢Oã8òò¢¥KK^Âýy?>ÿü½;?ÈU¬˜ó¥ Õ9·åׯSýúdm­©áãìK·páÂ>}ú̘1ãeKlÄû× ßüýýýÖ¯_šÊU¨píÑ#צMëÕƒ…E,-aa[[88ðïû8.sÌ“C‡ä†††¾¾èØ‘ÇXÂýµÚ¸q233£ˆèÌ>ÑeÉάH‚™ÇQO›]‰Byó0ijÕâ¡öÝ»áå…¨(8:òP{é½yó¦ZµjU«VU%9uÑ¡óG^Èår///‰DÒðÀQ£Fé肵9xÐóÀ{²°08u ¼®·ËÊʪ¶s'£yóXbÓ –xÃi‹“•à(â; ÀêÕX·¾¾xð wEšÖ¤¤€…EîŽã! ]Sî¿åUJJŠ··÷üahh¸qãÆeË– 8ï Š'àüyñ˜1öþþœ••௉M¡P|[»6nÜ {{̘Ác$eÞr´1FŒ_Ç"S7zfÎD߾ؽ›ŸŒ¢ZK~ù2(•Ø´ qq<„¡kXŸd9uàÀ1cÆ899‹uéøÐ¢ÊÊ¢Aƒ§Ogš™™\¹‚‚ÎpÒ–kW¯šxx4#R®X!úþ{~ƒ)ó’8ô‚DÏM±Å¾ãy'8‹cçN˜šjµÞ+°w/Z·FÕªøö[T©¢ÕÚKIC}’l.Iù0xð`™L¦T*'MšøégΞ¥^½ÈÎŽ„B22¢Áƒ5æ'ÌŸ1ã‰j¿æJ•xÛªá'O ³¶VÛ¢'¦PÿÉ©a9IhS2ß¡¼ÅqÔº54{6ߡ蕒ßöI,·•#J¥²~ýú~ùå—¢>³fMîVä#FPäî®É?íù;—äôü9¿Á¨\¼p!³^½œÍ\m¹œA5%T]B'tæÏ‰W¯hÔ(öçMñ°ÜÆ”Pbbâܹs÷îÝKD¾¾¾K—.ÍÈÈ(Ò“AA¹ÇNšDDôÇ<æ6ŽãR#"¨}{Òèõk¾"É+33ÓËÎŽ™½=efòNù²'…œ$T;”îgñÊû¤yóøBO°ÜÆ”ÐÉ“'8885¥½3{vîjš£G‰ˆ’“éØ1MùIÙÙÙ 26&€jÕ¢ÐP^Âø˜4))ÊÖ–nãF¾c)$“„š‡S¤nì6IDááddD]¾Ìw(ú@C¹Í“,³|}}»té"•Jûôé3mÚ´ãÇ›˜˜¯ˆû÷s_ÛÛ@… ài:eJHÈŒÿm••Y³&®\“/a|ÌÒ××1!Õª &Mâ;–òh‰5Ú#V—¦MV­Š;±n<<ø¥c¹­l"¢åË—_¼xqóæÍ6mÚÔ¦M›b—’””ûš¿¹”2™ìþ©S6ýûדÉ2\\LnÜÐEª~úé—ÌŸ##¾Ã)ÄlµGMÉ13º‘Ý0z4fÍBf&¾üW®ðM¹Är[™"•JçÌ™³jÕ*@ðóÏ?¯]»¶¨çøåK¡P_h%$“ÉÆö™YŸ>xö -Z˜Þ¹£;£(•J‰OÕ””ŒŠñõ×|‡S~Y ±Ç„8“É|G“Çöí8rcÆ ;›ïPʶ¾­L èØ±£……Exxx…Òl±r%öîEpð‡×«TÁ›7¥‰°ØBB›6µIIÉlÜØäÒ%þþÍK¡PÔ®-~ý»v±ÜÆ»+Y%ð³ú™ñ @©Ä¤I˜:óŠÓÐú6Ön+ ._¾Ü¹s縸8åË—_¾|¹T‰ €µ5†GÅŠ¹WFÆ‚˜>½”¡]JJÊE‹Ð¹³MJJV›6&×®éTbKJJz¹x±øõk¸¸`̾ÃaÐÁ‹m@ÀœÜ—ñ @$®]hÜ£O¤¥ñP¹¢Þ©) /zöì `žÚ'7nœ;OòÊ5^(ŽãƸ»G©ªîÖÒucã÷<ÏŸÿZÞ¾}|ÇÂäú!œ$äNZ?Ÿº GÍ›³cØ ¤¡y’z¸ÙHHHXµj•‰‰ÉòåË×­[×®]»Y³fñ”Ú?Þlduïn|ò¤NÓhùü¹3Y½ºÉ¨Q|ÇÂäZbƒp.fâë8üϦ:°—@€Ã‡±r%/æ;”ò„·é«'Ož4iÒD,‡††:hhzE“&xø0çõ•+hß^#µ¼/44tã—_®{òD(•Ò€‚߇¡ÎœeòŽL†Úµ†C‡0bßÑ0ïIã0 /³ÑÃÛìukÜeëV˜<™ï8t ocàìÙ³M›6 nРÁ/¿ürãÆ M%6žl9rÉõëB©#G þüS[\\Üö–-†zõ0|8ßá02b¯l„8›õº4mòÞ=LŠéÓñêß¡”,·é™#GŽ>¢•+ùެ0/ïÞõæ8‚E‹t63y‰€_ìPׯ²1%J¾ãQ±·ÇÙ³¨SæÌœdÔŽå6Ý’˜˜8iÒ¤¾}ûXºtéš5k¶oßÎwPo=ŠjÕж-æÌAíÚ03ðaPÿ×…B‘“Û¾ø¢ú… ;är!·j¼½Õ²zu{õÊ–(»Y3ôéÃw,LQ™ ±Ç¶"\ÊÄÚ¤O߯5ññððÀÔ©8žïPÊ$õ.gJL¡PQ\\œµµµÁÓ§Oy((ˆœs÷%Y·Ž^¿¦#¨ysJH ":~œ:q¢Ø%ûûVµjòòå$@ÀmÞ¬öðÕnýÒ¥2 è̾caŠívÕ %' Nå;”<Ö®¥ñãI&ã;^±³I˲3gÎÔ©SçâÅ‹DtâĉçÏŸóÐÕ«¹Y-ïG»vÔ±cîmôóÏÅ.|üxÎ @B!íØADN[¶P·nôÕWêúG¨ÑÓ§O …dµlÉw,L ý™JNªJ7tïtô­[).Žï xÂÎ&-›TCkwîÜyñâÅÖ­[ôíÛ·N:<‡Õ®ˆòùpv~ï6¡\1èe2; ; …X¹ññhÙNN˜2~~8y²$ýœVÓÚz‘£+øŽ…)¡Áæ˜` aRBuiÚäªU˜<_|¶I”±ý$y“’’²hÑ¢‡^¸paöìÙöööªleÛÙo¿í‘œ ss¤§ íí1o^Όѵ+ú÷Gß¾º¶²M*•Vؾ™™èÔ žž|‡SöE+±/åW ™C3!œÅhkŒ‘¨ZŠ_Zó­ñ:~™ø*Ça¡ÛO˜€¿þÂôél~’:±ÜÆ¥R)‰üþûïñññwïÞmÞ¼ù¤I“øŽKã®\¹’ºs'€œÓ>bb`m^½Ð¿?zô€¹9¿áäÛ‘#·œ9c`ùr¾c)þËÆöÐ͵ ÈáT:ÊñP޽©Øh‡^¦%,YülAÑx&ÇÔxìu€.üek‹[· "%·n¡[7¾*tãï–òäôéÓ 6ü÷ß---÷íÛwÿþýæÍ›ó”6pסqãb1T­šÓƒC‡0x°Î&6©TÚ< À\©”µo¯Ý¢uÍÙ¨Šê¡Ú>í;+l³ÇwVXaƒs•a-aV<¢KÑim&À{؉p)«tfÚ¤PˆÔT´iƒ>}píßÑ” ,·iOVV€7oÞ<þ|Û¶mzöìéææÆw\Eæïû÷Œýû¡TbÕ*(8}ÏžþÇq“&M2d(ž;wî , ›7ÃÓ…l°rî>ÿöö‰`lÜ4˜ IDATÌ×Wd²iÀhõj^àO?ËÂZä9ר¢½Þ¥I8“Qª’«ˆ±Ó†ìJÁo©¥*J,,н;êÕC•*|‡R6¨wj “/©TêååÕ A¹\®P(<(—ËùJ{^½zefff``XÔg֬ə™)шT£¹»k2Æüݺu+èóÏ  =´_».¸EN’œ{YZªô¥œ¾‹'÷ÞÅíÒÜH–$¨¡–ci9Ó&¯ëÌ´ÉììœSx=¢l9[UÓ44O’ߦYr¹\,+І †††úûûwèÐï ´‡ã¸„„{{{??¿ÌÌLÕšôO{òåÌÀœ4 Û¶áèQ¬YƒÀ@Fû±Á:ì¿zÕL À;pw×ríüºœ‰½©¸•…Ì÷Cˆ€bný¶0ŠÐ<êh‚Ÿ×´EŠ5o¬ùÆó¬‹C¾V'c«VBœ¨g™{pè¾þS§â§ŸøE+4t~›Îü–E~~~S§N;wîøñã÷ïßokk[»vm¾ƒÒžÌÌÌaÆ=xðàÒ¥KÝŠ5>þ믹K ºt€Ï>ƒXÛ?«D´ÄÔÔ ÈîÞÝ œ%6¸â±™o{$‡˜ÃQÄÛ0FÞ½ü›¨éö9VÎÆ¹Œœi“–º1DS·.¤¥ˆÍœ,9–Û4"++ËØØ8>>þåË—¿ýöÛøñãÛ´iÃwPÚ¦T*ãããSSSjÖ¬YŒ'ïßÏ}mo*`à@5Ç÷)\xxÀ«Vi¹j]ÐÉLp. osÛs4-QR™o™VŸ¾­Sh/fâ|fÎëêbt5)I›ì0$ä˜}:ñ ±ys7ÅÔ P¾‰CH¶†++''¸ºâÆ ¸¸ÀߟïhôMùê.S¯¬¬¬©S§ž8qâÅ‹]»v={öl·nÝåubõïßÿúõë …båÊ•%ÿæø÷_ÄÄä\ñòÒÆn ÉÉ Ab"€¿þú+yæL1õëk¼j¦P ‘ÊiiãwVUàd:ÆÇá¸#*èÆ_þÿþ ‰6°­L‹‡å¶’ÉdÇ™˜˜H$’”””+W®ôë×ï³Ï>ã;.> ‚7~÷Ýw3U‰A¿¨:}„B¥Òþ' /æ9ª²b¹ –Û”ðÙmöÐÚ \°Öa <Á+¿9¨sÒJ‰-] ++LÊwúF7þ2Ñ=gÏžíÞ½{õêÕ]\\z÷î}óæÍw_ºtéRÆ üñGÛ¶m{òäI¿~ýø‹”AAAnnnÏŸ?oÑ¢E@@€½jÖ¾~Qí` h 0b\]°±E*03#bp"]K5 °Ë•D¸•…º1mR,Æœ901Á®]X¿žïhôËmùèÛ·oÏž=ýüüÂÂÂBBBN:Õ¦M//¯¤¤$ÆÆÆÁÁÁ¾¾¾J¥ÒÕÕµV­Z|Ç˳eË–-Óëù„€‚ñíÚÑÁƒ04ªþ9¡¡hß¿ýÆsxüçi¸È n@);Sð³‡R16ijú{`BÜÿٻ︦®÷àOÂ^2D†âD@DTpàB¤ uT¨~u1ÜVEжNÀ:°*‚ZÅ-¸¸T– ”=à IîïôG­µŠ’äd<ï—ÄKrï§ιçž.5@b3¬¨ÜNÍÚRpHip–áB³l25<=ÁÛ^¾$ED`mûØüùó£¢¢þ}üСCƒ~ÿþ½Íõë×¥„¬Í˜àÕÕÕÀ¡C‡–,YÆm^#¢8È/,›@ãp8³f¡!\º@b"a»TÁèöÁ]‹»ÿÿôôG•«™‚Ùe L‡ª0Q î4A2/êPÌ¿^S Ðå‹f²°ShþUp»éËïKKظŽIÚÚ¨C°¶ý“É ÿ¯¯¾yóæþýûààà iO­ý[bbb÷îÝ÷ïßß©S§½{÷* k“šváp —ºú ##C÷ò‚9s`ʨ®†™3!!AØÚ¥ Ì<h¹…ÔÁ°b°*‚HÆ?Þã_²4øŸ2€*nêÂ(^ì¢D½¾ÉLxýXÛç}§+Õ€ °¬^ DzÉ_~Y³€Á€À@œ)ÿ2¬mÿpþüyÎÿ_Ãd2ûöí+È<Â,>>¾¦¦&^<šMqç$iEŸ2¦N…ãÇAI ÂÃáÄ PQ!y8¤ å@r4P ³"Œÿû oYp†ñWaã2–^­ÀØ« }d@•žÀžGûlµß U˜¤ Ì/û{ã1â&Lؾt¡'éƒ|þ /^¼ø–G’ÅË£G¬¬¬Ö¬YÓ§OŸ &îÂwïš5àç¼¾(»µU ^¾¤¤¤hW®@s3˜›ÃÙ³€¿ÊØ+|®®Ä7ÀŠG›ÄJâtùræöh[6™Òžåpª‹P,›Ü¼Ö­ƒ3Hçz8nûƒÏ¿áëöüGQQQ£Fš1c›Íž4i’€n:æçƒ»;8OŸòãôõµµÀ’¢±ÙÐÜ 3f@|<¶ö¨ç(}ðƒDœfËähpP t¥!©Ö DzÉáÃáÞ=èÖ RR ¦æËï—XXÛþá‡~øÌÃײ²²%¯×ÉGzô衬¬ljj*Ð¥4êêpàøùñéôjªª ÂfÿµÔúÔ)Iž‡ü*²›ØGê¡Jh¦ïxBK k" "p¸Žt Ó!2lmañbÒQ„Ö¶PTTüÌ$›»»» ÛˆˆˆÜÜ\33³ääd>®øÏÌüÇÎçIIPXjjÜ«ùaß¾}·¹;™šBR,\ȧ ‰¥!ò°F 6TÁò ª†ïASì–ݘÊÂnM l®þ»ÕYVV 'Êʰ¯¸°âmo1Àf³Í>µ=î¨Q£HG#)**ŠN§wïÞ½¦¦†—yøøÄŸ'(Š¢²³)**ЇlhhÐÔÔÜðÆÉ‰jhhïÇ®_§œœ(MMŠN§ää¨iÓx §=5T·Bªï*›I: EQõîÝ_/øú)ÜvÛúúú¼=-ŽÛ>F§Ó322>³};8:ÂÕ«P] 3f€®.|i KUaŠ4p`p,›ìÚª«aÚ4=Zõ`»¡Q”ÀvkC"É××·K—.‹/æp8t¾M ¶KNôí QQ¼Z'É`0˜L¦†Æ×ìu˜™ =^äé !!AAðä O"!aÖBÁôRxÖƒäàT%½l²¡ €ÒRˆ‹ƒ¯m,<ŠŠŠ ôõõ¹8^ÁqúœÄÄÄM›6­\¹²  €paãƒßÿÝÐÐð3OëÂÑ£?7;f Àøñ°~=ïÃ!áÓ¶l2¹Ö Á²I%%ˆˆ€§OE¸°ñ¸ý´B¼BQ“É´µµ :~üx=H'â½¼¼<ƒaôU»¥¤üýš»+´ª*LÊãdHXiJÁ1mP¦Ã9„ Á²IKKèÝ’“ÁÁák°Ö6ô ,kÖ¬YÎÎÎ---kÖ¬ùñÇI'â‹'NdffÚÚÚ~Ågª«ÿ~-ñû®I¦>2°O¤¶UÃÍFÒi`͈…­[Iç&XÛÐ'ÇÆÆ&$$dddÎÁºuðë¯ÁÁ°v-\¿Þ‘ó•––®]»¶¢¢â«7QÃ5×`”x©`ed3¿ü~~;t~þ°áà‡p- ú‡–––‚‚“ôôôúúúaÆ‘NÄ«W¯Þ¹s§‹‹KDDD{?³u+üù'¼zõñq==(*âm<$|*á4ô¤áŠŽP<ÕGQ &€¾>é(_×’´×œ9sh8pà¢E‹LMMUTTdee fÍš•™™I:¦0jllüþûïíìì²³³-,,ĵ°ÀŒ3ÆïííýŸQW‡éÓ¡K—¿Ì™¿ü+Vð< ›5ÀFŠYà^L!#lÝ ‹Áüù€Ëq“É<}úôܹs¹UPPðôô´±±‘——HLLyyùèèè±cÇ’ *|˜Læ¤I“ž>}Û¿Òqø¥©©IAá[w•·´„´´¿^?xÇó*EÕ˜ü Y0U viSSàïß}G8ÉWÁq[{ÉÊÊöëׯí¯ÝºuÛ¹s§««ë÷ßùòeîµæææŸ~ú©ŸxüuuugÏž•••=þ|||¼¶7oÞèéé­^½Zü~«C‚§N‡ÃÚ B‡ °ô2E55xô¾û ¸˜pâݶ}†–––££#÷uqqñÕ«WÉæ,ËÁÁaÆŒ'NœPTTìÓ§éD|tãÆÚÚÚ²²²ÏlŠPûõþÿe“Ûk šô²I:22ÀÜ\]%½©dÕ6°´´l{-&}5;LZZÚÓÓ³ÿþ’0Iëææ–ššºiÓ&ÒAø©ëÔX]i¤—MEAS”–NB–ÄÕ6==½¶×ùùù“ƒ×¯_Ï™3§±±qîܹ=êÚµ+éDü^TTdnnnhhH: +n`¦ 4SàV%Dw›TQ[· ) Äý»ù $®¶}¸ˆ ¾¾ž`a0sæÌãǯ_¿ääøÓ;Yh¼|ùrÁ‚¦¦¦5ØÒñÁFu*¥lXXMDoæöì øùÁ°aÐÚJ2 AWÛX<{+++K0 Y:4aÂ?¾õü*2223fÌøé§ŸÔÔÔHgAbHš!ZÐC2˜°ºÈ.UjiðpHHèà&"Lâ6 ªý`Ï5mmm‚IJNNvqq9wµuTTé8‚Àf³{ôèqüøq~]`ÞáæM~] 7;øU(¯JH%ý ­“¬_Û·Ž!x’UÛ"IIPXø×GçÞ¾ÿæ­Oè›§³¹Ë&Ëá=ÑŸ%¾¾0bLšD2”8JNNnû”••uppðôô\¸p¡ŠŠ ÷à¨Q£ FÛûgΜimm]YYIQÔ¥K—àòåËäâóˉ'ètú‚ 8é,‚“•••••Ń=|H|âω¿óèQJF†zû–E"«•¢f”PÝ )§wTƒ|ý|I ç÷=w«-}}}ÞžVüÇmjjjMMMçÎ;zô¨””ÔСCCBBâââ”””>|›’’’††Lš4IFFæÃÛrb ..ŽÁ`Ìœ9óîÝ»”¨-9–-[ffföûýÿ—aÀ¢>ñgæÌ¼­µví‚_±ÍدI„hAOx΄U¤—MîØýúAXÑ‚%þë$õõõïß¿ÿU¡Óé1Ú¯æÂ… ?þø£Ýµk×FŒA:Ž@µ¶¶š››gffŽ?^@—\¾llà·ßt9$ÄTépX &—ÀµFØ]?“{ö¤{wàp€§{ ;ñ·577“Ž@Ø Aƒôôô$ðy>™]»v¨ªò96‹nn ­ €$ŒyŽÃáܹsgùòå}ûöUQQ¹ùÿ«rêëëçÏŸ¯¦¦¶aò Û¯§ Ô×Â%rË&§Mƒ¬,ؼ™XÁÿÚ&–«BÚ),,,99ÙÀÀ ))éëz•‰…ØØØ)S¦dffÊËËóýb ¸º‚½=øûóýZâ®±±±©©iåÊ•††† cÏž=ÐÒÒ2eÊ”ÂÂBƒ‘'RÏW ‘‡-@¬­„rË&Œ ¬ f΄+Wˆe$ñŸ“”XQQQ¹¹¹’ù”ú¶mÛîܹcccóaÏ#¾¨¬˜8TUÿÞB[¬¬ø{]1¥¬¬ìääîîîׯ_¿wï›Íöòòòöö7n\EE… Fá<õ£2d2!¼ÜÊáŠèú¹{îœ:ÏžÁ„ @÷qÖ¶ÖÖÖœœœ¶¿644ddd˜˜˜ÈÈÈ|òýqqq)))uuuááá³fÍ b±XW¯^?~|ß¾}•š÷œœœ\]]¹kd$ÐéÓ§÷ïß¿lÙ2¾_);ž=ƒgÏþqÐÙ¢£ù~i±fggG£Ñ ÆîÝ»ÕÔÔÆšš¤{€~_ xË‚ÛM° Îë€"‰IkOOxó/ÿÂbÙw{þüùGŽùèàˆ#¾vE‰ˆâp8‹-ÒÐÐØ¶mé,Äp8œ¤¤$ÒAPG™ššfgg¥§§‹ú™ L-­0^h‘¼!²²0h¹À¾ÛíõçŸþûY )lðìٳÇïØ±#77—tbÎ;gkk»`ÁÒAPGqWöŽ?^Ô (Óá°6t–‚°ƒ\/ŠK—`ÄX¸>Ø7^ ‰áœ¤Äâp8ÖÖÖÔÔÔïöÙŸWUU¥¬¬lmmM:ê(HKK#„7 ¤á€ü¯öÖB/˜ªôåðÜøñл78:‹õ÷>qâG ç$%SSSÓ?þøöíÛ[·nIì ¶•——«ªªJàc⤲²rôèÑ µµµÿuË\äD0À«dhpBlø¿†÷ßš›»v¸íA8'‰>§®®.++ëõë×¼ýÿCä°Ùì… &%%iiiaauK—.Ý»w¯ASSÓ“'OHÇáWeXØ Z)XToHL ÊËCA88ÀO?¸º``my Ož<éÒ¥K\\ÜíÛ·û÷ïO:I§N:|øðÌ™3%ù¹FñpêÔ)SSS;;»‘#GÀÝ»w¹ÇcccIÆâ‘_ÔÁ^ª80¿ êIl‚$+ Á;PRBàꀵM´544|÷ÝwcÆŒyüø±¡¡¡¥¥%éD„9;;ûúúHII‘΂¾Zuu5÷ÖZnnîåË—ùåàÖ¶ëׯÀŸþYQQA6$OÐöh‚‰ ä¶ÂÒ ü/bzz ÙÙÐÁÞB ï·‰6Š¢ÜÝÝoß¾}ëÖ-CCCÒq+..ÖÓÓ#}»©S§^¼xqøðát:ýÒ¥Kêêêðöí[n;*GGG?á#ºŠXð} T²Á³¬S'“áæMÈÍ…%KÈ\øv¿M|WɈ»ÊÊÊ3gÎ,Y²dÿþý%%%¤ÖÜÜlccÓ½{÷‹/jii‘Ž#¹Z[[‡žŸŸß©S'YYY%%%yyyEEE999iiiUUU™-[¶|ôÙ‘#GÆÆÆª¨¨>|˜[ØÀÀÀÀÝÝýÔ©Sºººûöíø?éKC˜Ì(…u`(3” 'AF¡W/A_¯pÜ&’Ølö!Cž>}¼|ùrÒq„ÂÓ§Oǯ««›ššJ—„}„Xff¦µµõç·)WQQ©««X$avŽ«+Aš'I,›\ºôôà矉-˜äÓ¸ k›¨ºvíZ``à¥K—ÔÔÈuÎ2µµµEEE|ß=µÃÎ;W¯^-##ÓÚÚ*//?iҤɓ'KIIÕÕÕ±ÙìššAl‡&"¶VCh¨ÓáRW0$1›FQPR]»¸4Ö6››ûóÏ??~\]]Ãáà…+""¢mƒ]$ (Šrvv¾víš¶¶vYYnÙ²eƌշ8åp³zËÀ%Pì·uQ¸¸@U¤§ƒà·ÁçÛ€»»{LL̯¿þ Xظêëë—,YâììüðáCÒYÐ_h4Ú¡C‡444ÊÊÊÖ¯_oggWXX8sæÌ~ýúEFF’N'tè»5¡¯,äµÂ/›ÔÖ†êjhn†ü|Á^˜¯þ½õ"NÍÍÍE½yófÖ¬Yõõõ¤ã‘–––={öüð䃠>}”””rsscccÛ¦‹‡O:Ð)j¥¬ÞRÝ ©U‚¾tVÅ`ú¢\Üáš¾¾>oO‹µM4ÄÇÇkii]¿~t¡ÓÜÜÌf³I§@ÿiúôé0lØ0‹Åd2CCCutt€F£¹¸¸¼zõŠt@áò¤™êýšêVH¯#põˆjåJA_”Oµ 'µDÃÙ³gËËËOž>~èСoß¾õðð2dÈíÛ·‰„4€ß;CYÈo…Åå ÈVoß‚©)89Ac£¯Ê¼-•ˆW.\¸P^^NQÔ‡Ó8èC+V¬€Å‹“‚x€ÃáDDDôìÙ“ûsÉÞÞÿÏ/aQƒßRÝ © •‚»(‡C BõíKeg èŠ8n“ Ó¦Msttlnn–ðž5Ÿ1hР=z¸¹¹‘‚x€»l2;;;44TKK+..ÎÊÊÊÕÕµ°°t4bºHÁ!mP ÁÑz8V/ ‹Òhpédd€‰‰€®È'¸/‰0ª®®?~ü¼yó-ZD:‹Pc³ÙØËFüTWW777+**.[¶lݺuªªª¤s‘qµ—ƒ@x.¨-9øóOÈ˃€¾_‹Oû’àœ¤pñõõ完à>©>©  ÀÜÜüìÙ³¤ƒ >zóæMÛBÊÎ;Hì7ÅŽjª[!eþ†zÅÐss)JJJ3“8')þ¢££ýýýg̘Q^^.'ømÝDÇ¡C‡222._¾L:â#î²ÉÇ3¦²²ÒÇÇÇÜÜ<22’’¼©¦ŸÕ`’Ôrà§2¨H“îÞ½aÓ&8sF„g&qNR(´ýWX¶l™««+ÙÿóYX@S›ÿwøxk›€p8'''??¿   èÔ©éD"£¾¾¾¡¡¡¥¥¥oß¾¤³ Ñ ««š‘‘áââR]]íããcddÆ•Ìí6^Ö¨`yä´òñB½zA^ÄÄðñ!nÞÂÚ& t:}Ïž=£Göôô$EĨ¨¨$$$¤¥¥©©©‘΂D‰‰‰IDDDBB°aÃŠŠŠ<<<ú÷ïC:-Q…éÊÐÀÿe“ݺAY¬\ ii|¼ ¯`m㻤¤$ ‹Â‘#GÞ¾}@•ØØØ 6ÔÖÖ΂D’­­íƒ"""zõê•™™9a„qãÆ¥¦¦’ÎÅK›5ÀFŠXà^L~® €à`ðóãã%x†·mп?<<^ÅߟRR¢?æÍÙ°7©ˆIMM­¯¯'DT?¾{÷î»ví"‰!}}ýÐÐд´4gg窪*ccãcÇŽQ"¾—Å(ðVÀÊ Èæ[« &!6–_çç ¬m¼Ïb±Ö¯_éÒ¥ýû÷“Ž#ª †’’é Hlõë×/:::66ÖÒÒòõë×?ýôÓ!CîÝ»G:W‡xt‚ÿ)C Ê¡‚?Ë&½¼ 5UèŸãæí0>}ZZZzΜ9l6›t‘—œœÌd2I§@âÍfGDDr*ÚÛÛ§§§“õíZ9Ô%T·Bjò{ª™Ã¯«Sûöñà<8')LLL”••MMMétüwûX,Ö¦M›ÊËË­­­edøßÃI<î²É¬¬¬€€55µ¸¸8+++÷ïß“Žö-¤i¢†Òð¬VU?¦Y™L0–,‡ùpv^ÀŸ¿}|||êêø¿]#¯©Óá°6t¢Ct#ì«åýùeeÁÓfÍ==ÞŸœ7x; ”XÇ€ž={âZÿŽKIIqttÍIbÞhjjúþûïÝÜÜ\]]Igml6[JTv¬Câ.99ÙËË‹»ºÄØØxÓ¦M...¤C}Cu°©äi¡ýey|ò’X·** *êÛO‚=n„EQ«W¯>v옂‚Â7°°uPKK‹™™ÙŠ+IgA t÷îÝØØXssó/^¸ººÚÚÚ>Ú[LŸ²°ÌRf ÜÊ „×Ë&i4ˆˆ€›7áÍŸ¹ã°¶uÈÍ›7wîÜéééYRR‚‹G:îÎ;/_¾¼ÿ>wÛ„„½½ý³gÏBCC»víúèÑ#;;;WW×¼¼<Ò¹ÚË_†ÊC)–AOçéºtC‡ ;ºuãåiyç$¿‡Ãáp8ÒÒÒþþþœ0aéDb"33“Á` 2„t„>ÖÐаwïÞ­[·ÖÕÕÉÈÈÌ›7oÓ¦MÜ *…\ &¿‡8)Â~- ñúüÙÙ + ßÖäœOs’XÛ¾Ekkëÿþ÷?ƒqéÒ%999ÒqÄDll¬‰‰ î÷„\EEŦM›öïßÏb±”••W¯^ݶA¥0Ëo…I%PÇŸÕ`¥*/Ï ÀôépâÄ·|ï· ‘W¯^ÅÆÆ>~ü¸  €t1Á`0fÍšedd”M: BŸ£©©üüùsƒáïï/O{ÊÀ~-Ø]—xyf{{PV†N@¨J8nû: ïß¿ïÝ»÷ãÇåää,--I'%%%^^^oß¾½{÷.é,µ×£GÖ¬YÃÝ6ÖÔÔ400PÈoO„ׯ*£ÁÙ.0€wSNMMðÍWœ“$¯®®ÎÙÙ¹  àÁƒ=zô G áHäPuîܹõë×sW—ØÛÛ 0€t®ÿô[«m)¸¬ºÒ<;íóç°};lß_{ÿç$É“––æ.†d2ù¶Ã¶Dòõõ5kVAA6$rh4w¿.nãÓ¸¸8kkkWWW¡½aá«Ã塌 Ë¡‘wC›uëàØ1س‡g'ì ·µKeeå½{÷¦NZWWWYY‰ƒ6jnnÖ×ׯ¬¬|ðàÁðáÃIÇAèÛ1Œßÿ=((¨©©IVVÖÓÓÓßß_MMt®180¥^¶‚£"„hñfˆ“˜‘‘°zõWïÂ…s’Ä455ÙØØdffž;wnòäɤ㈡üüüóçÏ{yy‘‚mÚ´éðáÃl6[CCcíÚµ+W®¶ÕoX0é=Tq`¹*¬æiñ­ª ¯x?ÎI£  °téÒÁƒÛÙÙ‘Î"n***²²²zö쉅 ‰ nãÓôôô &pŸ [ãÓnÒp@ dhðG-\âѲÉêjøî;07‡–Þœ°#°¶}ÎË—/çÍ›×ÒÒâæævçίúmµÃ–-[ÌÍͱ¹6?¦¦¦QQQ±±± xóæ ·ñ©P-"[5€X[ )¼¨Fjjðî0žÎƒ³uÖ¶ÿDQ”‹‹ËÑ£G·lÙÂ6¥ äååíííIAˆ/ìííŸsæÌÀÀÀ®]»’Îl·2¸Õ¦²pN”x±×Ç  ¶ëÍx¿Mpúôé“••eiiyñâE,lüðúõë~ø!## ’²²²+V¬à6>•‘‘9~üxïÞ½…¡ñ©Àš`,YLø¹8>ááÃ0bøøð [G`mû„Ý»wçççïÝ»—tq¶mÛ¶ .‘‚àhhh¼|ùröìÙMMM½zõ f±:gΜ¼¼¼€€€N:EGG›ššzxx”–– >Ìzu°W€*,(ƒúüòéåAA°r%ï’}%|Ž?>wî\ggç‹/â^½‚QQQAQ”––é  ah|ÚÀ©%Ó £àOmèàÏÄ/nÁ…Ïð‹­­­žžÞwß}‡…M6mÚôèÑ#MMM,lýÛ‡Oüýýûôé#àÆ§mË&ï6A@õ·Ÿ'?¬­áÖ-ƒ©S!7·ãÛ·KSDËîÝ»322(Šª­­%E"<{öŒF£)))UUU‘΂°KLLlëŒajj!È«'ÿÿ²É“ߺl²¹™êÒ…ÒÒ¢Þ¾ýëH¯^•›û·ñi¤äÎIž:ujæÌ™ººº/_¾TRR"G"TWWËÉÉ­[·Žt„DCTTÔªU«¸«KÆŽdee%˜KŸo€U MƒÚ`+ÿ-gxþŒŒ@Vö¯¿vêõõP[ :ýýìqÃcL&ÓÅÅeæÌ™®®®¤³HÜ[ ¡oÓÚÚzäÈ‘ 6”––Òh´iÓ¦ ¦‹d@5„Ô:.uÃv?µu+Ì ººl6\ºÆš((€œ4ÿó¼ßÆ,ëÿûß¶mÛdee/_¾Œ…M`¦N:tèÐ\͵#$>dddÜÝÝóòò|}}ååå###MLLV¬XQSÓáMD¾d­:8(B5æ—A]û–MîÝ ¿üC‡BN€§'L›aaP^ °ûìWÛâããÏœ9³iÓ¦ââbÒY$È»wïÒÓÓ³³³q BßFYYÙÏÏ/77×ÝÝÍfïÙ³§W¯^ÍÍ{Ðú³è»5¡¯,¼j…¥ОgÞf΄#àõk<nÞ„„ž=ÁÀ¸O4té¿°ÿ Aµ­µµµ©©iäÈ‘üñÇ•+Wô¾¶ó9ê]]ÝüüüK—.á´$B¡§§Çm|êââÂm|jllÆ¿”h® :Rp¯ ¶¶cÙ¤º:ÄÆ‚«+Ô×ÃĉP^¹¹0ož Çm’r¿­¾¾~Ò¤I---ׯ_WQQ!G²Aük[mmmjjªAllìÝ»wI'’,gΜ9 øñÇIgAHÜÐh4—œœœÝ»w«©©ÅÅÅ 0`Μ9üø%ÞY–ª‹‚ÅåPоÝ&W¬€°0–&¸óešš<Ïõib>'Y[[kooŸŸŸ÷î]sssÒq$÷!JÜ7!¨ªª nnnVTT\¶lÙúõë;}ø(Y‡QË* ªzÊÀ%PmßwöÕ«àê þ óæýã«8'ù-”••{÷î­£££)°ßÐΟ??`À€ØØXÒAÜÆ§/^¼pwwonnæ6> d2™¼º à÷ÎÐ_ò[aIy»–M€“ܽû× Iœ“ì¨âââ°°0))©#GŽÄÆÆvíÚ•t"ItèСôôôW¯^‘‚¤èÖ­[hhèãÇG]QQáããcnnÉ«):yÔ†®Rð 6Vµ÷SÖÖ}úà:ÉŽiii177ÏÍÍ=räÈܹsIÇ‘\L&óÌ™33fÌ‘‘!!‰·zõjîê’!C†lß¾}Ĉ<9ós&L+& 6iÀœv/íׯOŸ:) U`x”ÃËVž„å%±ªmEÍ›7ïÊ•+[·n\žGPçÎ §OŸN:B½½½_½zåííM£ÑÂÂÂz÷îíããS__ߑӮTƒIJÀàÀ‚2¨â×¾(ßH|î·µ´´ÈÉÉåååmÙ²%$$D^þ›Z2 Þa2™ÒÒÒøBBååË—¿þúë¹sç(ŠÒÓÓÛ°a ¾¹3s3ÓK!¥ËÁ©. óõ[áý¶Ï¹zõª¾¾þ;wz÷î}äÈ,l5775êàÁƒRRRXØ6FFF‰‰‰#FŒ(..öððà.¤ü¶³ÉÓ L t¥!©Ö·{Ù¤ˆÉž¨¨¨ŠŠŠ+W®‚àôéÓ÷îÝ Å†Ð2dÈýû÷¯\¹Ò§OŸììlWWW{{{îÖ”_K[ i" "ðg‡æ8yIäç$ÓÒÒú÷ïÏf³;6wî\Ü—8Š¢"##»té2räHÒYB_ðïÆ§={öüÚó\o„Eå@8¨ c¾âƒ8'ù 'Ož´¶¶ö÷÷—’’š7o6âž>}Êd2]]]±°!$ÚŸ(++GFFöíÛ×ÃãœÛ“¦Ýa•°–UÀ !X6)ÚµMNNŽ¢(î(ƒ:¢¾¾ÞÑÑÑÈÈèýû÷¤³ „¾‚²²²··wvv6·ñiXX˜±±ñ×6>]ª S” óË ’Í¿°í"ªµ-""¢¶¶vÚ´iOŸ>ݲe é8 ¨¨H[[[__w8CHqŸfdd¸¸¸TWWûøøµ¿ñ) °3XÉA <ÊIô~—HÞoûóÏ?.\8|øðÛ·oKKK“ŽƒþÆf³ËÊʰ¶!$ê>l|:pàÀ   1cÆ´çƒl˜XïXࢠ¿wþòûñ~ÛßœÍÍÍÝÝݱ° ?þøcÏž=L& Bb ­ñiÏž=Ÿ>}:vìØqãÆ¥¥¥}ñƒšRð§(Ñ ’ëôÓDiÜFQ”££ãèÑ£¹Oj“N„þRUUehhX__Ÿ˜˜hccC:Bˆg˜LæÑ£Gýõ×òòr:þÃ?lß¾½{÷îŸÿÔ&XP@˜6Œûì²I·Á™3g‚‚‚¦M›VWW‡…M¨hhhœ={võêÕXØ3²²²îîî/^¼ðöö–••ŒŒ455õññ©­­ý̧F+À5ନ€l«ýDcÜÆápèt:‡Ãqss›2eÊ„ H'B«©©‘––VVV&!Ä_o߾ݼyó¡C‡8Nçν¼¼V®\ù™‘†w%œa€ž4Dé@çÿØÕKrÇm---“'O^¾|9N?|ø06a³qãÆ^½zEEE‘‚â/ƒÐÐФ¤¤1cÆTVVúøøXXX|¦ñé °‘‡b¸ |Ù¤Ô¶ÔÔÔ7n„‡‡¿yó†tô1‡“žž^QQÑ­[7ÒYB‚0pàÀ[·nÅÆÆöïßÿåË—®®®666÷ïßÿ÷;¥ip@ ºKÃÓð©hH¡ž“lhhhhhÐÖÖ¾r办žÞÀI'BŸöüùs333Ò)BÅápΟ?ïååõúõk°··ßµk׿ä¶Â”¨ç€:,êôñI$nN²²²räȑÇ/--ýþûï±° ¡üüüß~û­¦¦ BˆN§»¸¸dee¨ªªÆÅÅYYYyxx”””|ø¶>2°W¤‚ªáf£ ² è:_Íf744466v°{âŸÍ›7oÞ¼yíÚµ¤ƒ „ˆù°ñ)NÿdãÓQ ࣀ•‚Z6)Œµ­¢¢âÁƒÚÚÚ±±±÷ïßïÝ»7éDèÓæÏŸ?zôh///ÒAB„uîÜ9 ==ÝÅÅ¥±±100ÐÄÄ$,,ŒÅbqßàÞ þ§ üT%üßmRèî·ÕÔÔØÙÙ½zõ*..ÎÖÖ–tôŸššš¾¦•BH2$%%yyyqW—˜˜˜lܸÑÅÅXÌ*ƒÄf0—…HP HÎý6555''' cccÒYÐÊÊÊÒÕÕõõõ%!$t|ïÞ½ØØX33³œœWW×aÆ%$$HÓ D ¥!ƒ «+€¯ã*!ªm/^¼X·nEQÛ¶m»y󦆆éDè?]½zµ¶¶¶ººšt„â6ò ÕÑÑIHH>|¸««kUÁ«?µ¡baïç66ù[bb↠444h4ZddäG_MJJÚ¼ysÛ_[[[ L&“Ûéõ?þ µKRRÒû÷ïI§@ ;ƒ ¢¢ÿß õÊûšž…T÷Bê2ƒâNEêëëþ$>>>0oÞ¼¶¶¶öïßÁ‚mGØlvŸ>}@xÆm222{÷î?~ü¼yóHgA_pðàÁ²²²Aƒéèè΂vJJJÞÞÞ999îîîE………ýdÚÃ&åàU Y”l{N2hÐ ÈÌÌüðàÞ½{ÓÒÒJKKÛŽÐéô‹/ÊÈȯm |ÿþýwß}wýúu%%%Ò‰Ðç<È·555………}x\@ã¶E‹7®µµ ›ÈQVV>vìØ‹/Ú?3Ž’p--->>>–––ñññZZZ7nÜèÈÏ555GGÇm ­­Ý¥K—èèèNþÑÒ[@Ï·544Lš4iÕªUNNN¸â¡ÈÈÈ‹/úûûswiC¡/º}û¶‡‡G^^Fsss PWWïà9SRRtttºvíúáÁ¼¼<‡cddôÑ›ù[Û8Î’%KÆ7uêT‡C§“ß}-KKË´´´OOOÒYB®²²òçŸ>qâEQFFFaaa#GŽ| þÖ¶sçι¸¸¨ªªª©©ñïBˆ ƒƒƒeeÛµ¥)BHb;vÌÛÛ»¤¤DVVvݺuÞÞÞ¤:ó«¶±X,&%%åíííàà0vìX~\ñ‹ÅÊËË311!!$ìÞ¼y³xñ☘}úTAA¡¸¸¸{÷î¼"¥ªªJNN£mæIDATîCAIˆgÏž¹¹¹={ö ¦L™òÇèéé‘ÐÁ9É„„;;;6›ýÑq99¹ððp ‹¾}ûv,"ìýû÷]ºtÁE@¡444¬_¿~ÿþý,KOO/$$dâĉ¤Cý­CµMKKë¿¶„766ÎÉÉùæ3#²š››-ZôóÏ?ŸX@ ¡ØØØE‹½zõŠN§/]ºÔßß_ØV ~ûœdjjêgz¼xñ¢¦¦FØþiQ;………=z4==ýéÓ§¤³ „„HEEÅâÅ‹### oß¾¡¡¡#FŒ ê¾½¶Ýºuëóoxôè‘££ã7Ÿ4}úôwïÞ3†t„9v옗—WYY™œœœ¿¿ÿªU«„¶ã÷“äp8ü;9âŸââb==½€€ÒAB¢°°pñâÅ×®][[Û°°0333Ò¡>çÛ×|qe?î«+Šêêê,,,ÆW__O: Bˆ<îÿ~ýú]»v­S§N¡¡¡ñññB^Ø #ã6KKKMMÍϬ%Á›m¢(%%…Åbµ´´p[%!„$Yrr²››[ZZ¸¸¸´£ÐêÐ:É[·n988ü{îQZZ:-- ›XЍÊÊÊÊÊÊï=Š’ ã—_~á.ñ700Ø·oŸP-ñÿ¢=·4vìØÛ·oTÆ{õê•’’‚…M…‡‡ß¾}»sçÎXØ’d7nܰ°°Ø³gEQË—/þü¹h6àÕ~’uuu·oß–‘‘=z4¶øQeee½{÷®¯¯OOO777'!D@YYÙÒ¥K¹Küûõë&¢+'Ô¿ ¿ÆÆÆ½{÷fee=z”t„ QuðàAŸêêjyyy???a^âÿEXÛ@ss³¼¼<é!2rrr<<<îß¿öööèÕ«éP‚û"ooo[[[!ÉÁd2ýüü¬¬¬îß¿¯©©~óæMQ/lÀ×g·‘¨hii¹xñbQQ‘””é,!Áyôè‘»»{FFÌž={ûöí]ºt!Š7°¶!““ËÌ̼víZÿþýIgA B}}ýš5k:Äápºwï¾ÿ~'''Ò¡x ï·Iº·oߦ¥¥9;;Óh4ÒYB‚páÂ…eË–½{÷NJJjÍš56l¿õíx¿MÒùùùMœ8Ñ××—t„ßMœ8ñ‡~x÷îµµõ“'Oį°Ö64xðànݺÍ;—t„q8œàà`33³èèheeåÝ»w'&&ZZZ’ÎÅ/´Ù³g?~¼íïVVVƒ¾wïÞÛ·o[ZZºté2räÈuëÖõë×`JÄWl6W‘ $Ʋ²²<<<>|ãÇ éÑ£éPüE?tèЇÏêfgg+((øùù}ÊÇhˆ?æÍ›7tèП~úIII‰t„P‡477ûùùíܹ³µµU__ÿþý"× ›O¾PØ Û^0€ûB]]ýÀ~~~|K…øåáÇG]·n]KK é,¡‰‹‹333 d³ÙË—/þü9¶6_·qŸc:>yòdîk‰ZH*f† É`0TTTHgA}£ŠŠŠU«V8q‚¢(SSÓÐÐÐáÇ“%\>WÛé8¡v¹qãÆ¢E‹ ¤¤¤¼½½7lØ€“.í÷…g>éÑ£G—/_ÎÍÍ€àààû÷ï3¦­c6RRRÜ-ÿgÏžM: BèËÊËË—,Y  ³²²"JÄH·¶¶æää´ý½¡¡!##ÃÄÄä3‹Jmlllll} ‹µnݺ«W¯¾ÿ^EEÅÜÜ|çÎçÏŸ' !ôEïÂ… &&&aaaRRR¾¾¾©©©XØxÇmb¥­ÇÞ'}Ô]!DDqq±§§'·±óàÁƒÃÂÂp‹WžÃq›X™3gÎg¾jjj*°$¡ãp8ÁÁÁfffÑÑÑÊÊÊ»wïŽÇÂÆ¸NRÜôèÑãÃŽ²mh4ÚÓ§OÛÌ"„,;;ÛÝÝÛÓÑÑ1$$ÄÐÐt(±…ã6q“’’¢¥¥õÑA:†… !"ZZZ|||ú÷ïÿðáCmm툈ˆk×®aaã+·‰§;vœ?¾¸¸XYYyàÀ]»v% !ItçÎÜÜ\æææ¨¦¦F:”øÃÚ†B|QWWçååuðàAŠ¢¸K"GŒA:”¤À9I„â½ÈÈHn=“‘‘ñõõMIIÁÂ&Hø BñÒÛ·o/^Ì]âoccsðàA333Ò¡$ŽÛBˆ7ØlvÛÿN:…††&$$`a#Çm!Ä™™™îîî 0mÚ´={öà.‚p܆BÒÜÜìãã3`À€„„ƒ+W®DFFba# ×I"„з»uë–§§g^^N_ºtéÆUUUI‡B8nsæÌ¡}`àÀ‹-255UQQ‘••500˜5kVff&阡¿TVVΙ3gܸqyyyýúõ{ðàApp06!ã6aÁd2OŸ>=wî\î_<==mlläåå@^^>::zìØ±$ƒ"„Ž;¶víÚÒÒRyyy??¿U«VÉÈÈ…þ†µMˆ<~òäÉÙ³gKIIñéºL&ÓÏÏÏÒÒòÞ½{ZZZ7nÜèÙ³'Ÿ.‡ø‹BB#99¹í¿‹±±qÛñû÷ï·wssûð#C‡mmmå¾Þ°aƒ¢¢bnn®@C#Ä3gÎææfšyyùœœ>]ññãÇ@£ÑÜÝÝ«ªªøt!$8nRãÇ_´h‘›››³³3÷à¨Q£víÚõáÛ|}}ÛfK¦OŸÞØØxóæMAgEˆ×¼½½ ¤¤äĉÜ#çÏŸ·²²266æùµêëë=<Ÿ"!$Hvvv¶¶¶ðû￟>}zòäÉ:uâÉ™9Npp°™™Ytt´ŠŠJhhhBB61ƒã6!Åf³¿êýË—/·±±ùí·ßø”!Áóññ™4iÒ½{÷^¼xqòäIžœ3''ÇÝÝýÁƒ0eÊ”½{÷êêêòäÌH¨à¸Mä±X,777mmíàέHœLœ8‘;œ’——=ztÏÖÒÒâçç7`À€èéé]¹råÂ… XØÄÖ6aÑÚÚÚÖ° 222¸ËC>ƒÁ`¸ººÚÛÛûûûó9 B‚F£ÑV­Z?ýôSoKLL´¶¶ö÷÷g2™Ë—/þüùĉy #ìM*,æÏŸäÈ‘Ž1â3+J*++&NœhccÓvP[[ÛÊÊŠ_)¬çÏŸ[XX¼zõªGßv†ºº://¯ƒRÅ]9|øpÞ†DBk›{øðáˆ#>:èììÌ]ú…Ø·oß… nݺõm?wîÜòåËß¿/''çÿíÝKH2kðWûò-òÒÅAA˜VC ‚ (mW•-¢ 2j!­Ì.0EYm´V¶Õè‚Ð*((q!„AWr#µ33Ë9 9qÎsÎWœ¯™©ç·p!< á™ÿÌ;óº\ccc………ÿoBà'tð˲uuu.—Ëb±¼÷ØÛÛÛáááüy^[[›×ë­©©ù§p¿ xÊï÷g2™îîîw•_âo0‚Á R©ôù|ápÅöÝàà‹\.gµZ£ÑhKK‹V«žž^__×Ë‘c±EQ‡‡‡„‹Å²¸¸¨Ñh~Y^à/\“¾H&“ÞžÐb±Ÿ<6“É8Î………l6[YY¹²²‚•ß®I_”””LNN* ¥R9>>þö¢äÿ‡õz½ÛíÎårXâsÚýýýèèèææ&˲z½ža˜ü›ºà›ÃÜBå÷ûõzýÆÆ†T*¥iúôôÅyXKÂs}}m³ÙB¡!¤½½}mm­ººšëPÀ#˜Û@H^__Ýn·N§ …BjµÚçóííí¡Øào0·€`œœœ F"BH__ßüü|YYס€0·€¤R)»Ýn2™"‘HUUÕöö¶ßïG±Á?A·ßíïï×××/--±,ëp8b±˜Ùlæ:ð®I÷<\.ïïï‹ÿrÂL&m6ÛÖÖ!Äh42 ÓØØÈQF<ß»¹¹ÑétGGGF£ñí{†a&&&ŠŠŠfffl6Û8‡Ÿ‚? pldd$•J ¼[<:88 „ttt¬®®~xÿ6øž0·—‚Á`WW—Z­>;;S©TÙlvvvvnn.N—––.//`ƒÌmÀ™§§'»ÝN™ššR©TÇÇÇEE£Q‘HDQMÓ …‚ëŒ Hè6à MÓMMM===v»Ýãñ¼¼¼ÔÖÖz½ÞÖÖV®Ó€¡Û€ñxœ¦i±XÜÛÛÛÐÐpuu%‘HœN§ÃáËå\§aÃý6àFggçîî®V«½¼¼$„˜L&†a ×¹à+@·vvvÌf³D"y~~–ÉdV«µ¹¹9™LÞÝÝ%‰D"QPP_' ðè6øl™LÆ`0œŸŸÿËo¤Ri:‰DŸ– ¾Üo€ÏFÓô[±Éd²ßþ Ñh***òŸååå܆AÃÜŸŠeÙ@ P\\œ¯1•JÅu"ø‚~eíºþQ[ÄIEND®B`‚opengv/doc/addons/images/relative_central.pdf0000664016516101651610000003773513344612246020326 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝ;’&;’õZEÊ#$o`#sZ¤Q*ZÏu’·OÿÎ""³ŠC¥¥¶kײܼáp8üÿóãúLÿí¿?ÿúñ_þm|üûÿþq}ö1F©¿ÿãýûÒGýœý£´øs­¿LNŸ­–Òëøœë#¯úÙF€©~örÀŸ?J›é³ôû÷-•õT?ðî€ 3çç5êÇi ¦öy©C÷p਱‡ð”ØC<-|›ÄÏÿ‘çg©ýãÿügóÿ·ýgÿüøÛ?óÔÒèí3¥9Ûg¯)¦vcZþ,£}¤Qægª3·Ïzõ€¯h`ÞðÏ©ôÙÓS¢×[}Z8ðîƒƬ4?—j¸…UÛçëîãÀQcâ)áQÞ-|›„ûÏ;·îcvy¦ò¹â¤Ì ×Ê‘{0qhrþÈc0â@å@+Ÿ£ÜðÏyäë³¾JôU>ÛSû€n>ÊÄŸƒwõç,¾;Ø0Ì×Ï÷àvõoÃ7ý'›Ò?å>éhÍq}®õ-s»ý¦|Î@ôÏÔ`ÿä÷CIs^Ÿy|Œ¢tüœ…C2RŠf2%FÜ¡—Ï:©¾’áhÿª±Úg‰‚y¯Bõ9S€ÑMšiÅHz xÄ«“»®õÙr`ægó—˜àœ‚ãôë2Ú S#`,ÁS¢Ç “4ÈÒâ\®˜S}u}jÄÕÑWOœVlѸÅÚñÀp.îp0±¥DùLí£­GœsźµY?c4î¢3±6r4Y(X¹ÖƒU&Î¥5>Zìj¡P£;É-fs¥`«ÅBÌ\¦\tY×gŽJIZñS,j Af,‘£ÏEü©™RŽ[ø†µ¸M£8%æš\­À³±ã+¾åXˆ”¼ã»ÆT¯A Ñpìcœ<Êtæ&&V.¨^Ðìª_.•ÏŸp0M“T ¢`Ë%v'¹@Lc›k6·~ YmœQ!(*E£Ã˜l¿‚ñ¥õSaÄÊ^±Ym7„ÐàèšõóçÊù®Ñ>j/1Øþñë‡7v¶¶˜þUÞ˜ÚÅÞ3‚Âb À¼jåÇtÞ-Óƒ”F9•*‡0VjÕ7&ŽBj®¹ý†yí_&o{ÑlfûÁÄ$¥€K×Û¥'i}ô~I²‰ÕÏ+&h±@„ìsÀcZ$t-ÎØƒæ“;ÛÄ|é¸&øPº0û`ŠÓ'NåãÉ0ÅF?ë!’Ó¼Aq” éœß!Ù ª±$ÊÇ0º·?޳Š.S›Ç )Øç½ý}ÅÎõÚþ˜Qœá¬Õ Ƈ°Õ8qIŒ®ÀZˆ¦ñ¿ùØj7¬iuäÚ§DlCTh°Ÿž-s…h–5ðFµ ±«¬ï[É­œ½Á l/8É_`B"ž!|_ŸQ¨Ìž>`Ö,ŽÚqÃD#eJxŸ=6#~‰ãÏÊ”i™§Äñï…Ëc4v»ä©ÃNa°µ3¸ÔGp¼ ¤d!Y|N±$àY²j,.˜Rb)~àÔÄ©,ÁÅ®+*°½W¹á¨Àê\éU"Ö¼ñ¤ˆ µ)+¨3è£+>¥±]‹7ˆ·<àÅfå˜ c9`Y‚*+¿xpsÜYwl0gÝNQlM׸|Å–eºÙŽ 0H)VV*ǧv'ÁŒ>è`Q1…L`YßÚA}%Uö"&=ÈòâÔ¤slLޏ6̲ráäW‰ Pnqi+;¼xöâÍŽI}ÄဠG;…ÜËÁ=1HÄÙ¬Ó§BtÀЉZÐ4€ƒÕ¤XX¤Õˆ^c™à+¹¸DK .2ÕgÀ1­ †ä× ‰ë$èÒ‚-$n2è ˜iÆò¬¾kP<éN€zRZ{Ö›LlpŽCGY+g-h&æ×^èjÁËÁ–ôñ®s]pöw»Æ” ¢hðÔ‚¼‚äÚßnÔU«Iø‚ùr®A™;7°Ôvc„AÅ‚Ìq‡H>X@ìX:ÎûŒDsˆ‰!nL(2nO=ëÍ"¨ÏuuùˆÀ…ã—‹ÛYç´Ã³Jü‰§pF)!)ÖbŠ ¾œ}.eÀAXõ^Q,çxÃ?½î)½JŒq`õ!Ù"j0”¼i¸3/zõþ‹ËI£’ºaïv n\õäº)"Îë¼¼sqJƒ5¥}$ä«hª¯åqæ|ÃZ îǧkÒmB`ƒ±"¢J®ˆ³g6ëÓŽÍ;ìÍŠ{.n…ïÛ©'Ô+ì!mÅL㱑‚ bõj\¬×€¾nÌ@râ‚ÏWĸØþ€yjÅ1àÔï†DOI÷’*6®Ç,sj_0±¬1!0±(±¦ìJðoˆ»£¿ÿ¨)Ö%„†q¯ƒ¿~Ô+éÉ|0¿nLìtJ¥g?Zˆ] Ž?ê]Ä2N“v½‚ãÅ•—uCòþ‚Æ¿Õb#ëÍ#z^I£8¤ý`lBTW8'¼Ðc `dOˆ=qP™ÃÅAV‰ * L瘦¬³Y/^Fð¹‹gŽ<р±!Ãgž”Ð1œ58ð'±kHà¨×r{— 5¦Íx-ÄA{ฅ®r׉…s›eÕd€ÅÒ“‰\3˜ºRÖÔ$`NÙG¾àlÀÁíÊ R¡Yów¾çYæË°9@`ÄÁ ¸ÆÆÀtöĪUí¬®ÕË5¸|šU3󬈉¼Ž$~³×@}ß/A SgS{M å­´72䨋‹»~vwP$ ¥8"qW›¼b»Ê0ASÒ^`xÓõ‰V*"GœÏC‚™Ï-¿ifQ0óæ˜”h sð¢‰ð–7¬í¯Ÿ+¦þx,7-‹ƒQèkcBˆj,agñ%T-‰¼ÑjŒ›5g-ªºi4^ôòÙ½žhWýÔ͈¸|1‡Ÿ5u¹üŸWLKãÁdT$o”&é¢w=<ŒâäêÄ= b¹‹掣ýØÅL{Y²xÀV]u´a»B…à:÷·^Avƒ¥ ‘'ó¦@•µ$Õœ)d0’c’î£MIï¥HuÌ}©ÙÛÓâÒ㥅;ik‘·Ü5¤hqLu•àblík‹ãÄIaöÁ¹I¥„Ø>¾S®’YþúPÁÄÌÒôÖ"Ò=˜X ¥­»Æ•†- 8>Å®!©%RÐÍÒ;ïµéHÛœáLÔ€gÑE,K¹> ðò ÙÊ» œà·Z’Ìë„n‚‚¨Î¾HË[x„gvøÀ?Ÿ™nÌ{îÈûXç¸nDôš¹ˆ´¹×Ò‰h!x"±§Áß; ÌSOÚ¹†´®wˆîhÑ-|Y¢V\‚ñ1ò¸þ¼ÚqùB[£§åÏL$›\îí)¨[?¾o •I$ÐC`ã$þõ”döU:·òŸ®óë·V^˜²X úÕ.¨¾Zù vßÛà^(¨Z Ä !¦ždÒ6LAÑÿª!¤þÿ'¿‘nBp%tÀÉO¬賿8/âñ“ËNÊ:©Á¥x p@xÏÏaåNìK÷‘lÓÏ1Êi$opJ TñhÜSwí¹víÝ|l¾ÜwÿñCáÅÉØ|ôy‹¿¦¡=µ†Þ>î™· ¡ñZ›†@Ôü\õê¡Õ½öwÃ0±³þÞj£Ù^%Ç׫…bbyº¨Ò?ƒˆëEÎ ëtƒÏ,àµå™fCsòZ‚Ø8Xó³F«é—{WleêÏ"?ðÙ…³·énaïâÝǽÍ÷(6!œA:9Óx‘ÑžèMh{!n:ôJ½u/åMÊ{©oRÿzTcøÉËò‰+ß´¨ß—9QžÖsœ›*^YFLFˆîõŠkùæ”5!vÈÓµô³©º@CøÑÓœ'`Óõ‹ ¥ÁšƒûÑÔ1®$X–X7zšF 3«÷¦Ê@ìàú”f¤oþX´uw™U)Áe^­-äò‰ ËÕDpI†¸>­âZhÑ@è]{ï0·Q¥ÔõÉwÑ&Ìè*KžÂqÅ;ºöå"eMºz‘·ÎeOs oi–0ð„ýÇv­ÐqÌÚ™ûgÝžKZS©‚Ò‘æ¬t£U‹QY¼©l#‚¬KÒ°ì»së¡Q‹e_àyYISUä;Ëd›žñj(’ý’†„&ºJö+RŸÁÏâÄH6Þj™FÀX•% +¯—ýï}ns9?…PPËîŠXr`‰ÙðØÓãñRâ‚´ôõB^*– õ":p•äEƒA'­M2ؾ".2bô8Í:…$óŽ®YÕ¸´øº…y!]>ÃнÅ>žsø0A4Kv¸–ÙD,W·Ü¬j³¤ £oÁ©ã‰"9m·àr”Üû¬!&ݔߎýÿãuñ‚Š#{}#ÕiÃï-L$_² òZùV$^ì‚Õ‰LgûŒ ±u!®ÈHŸÅ­e¨È~õܯ¦Ó÷oµ ¢aá}bèío?ʨ’äkZJEÏìoêR/ ÏÅ,Ì+9XjÉ{H±à˜†®+A ý¨(w%ü#“{àI_îOؘ“Jñ&‰B±Þ—Þ£<î‚—š¥ÏÚó0‰Ê߯Ð;?ЀÖϽ(uYœ-¨A¸JKy[tµýúÑR’À^RÑC†j^‡5‹Í”L3çòXæ× ÜŒq­Ê†­õ“%N¿1±’hR+fBiT–ôº5¨TÊ©v¤Ïºô$“Š E™Ä™âaÒ®f…LpÆ"FÅmŸ¦Õa(w[<1&r'g–{2ҪZìë—Ô ;¾‚³Ù…8X$oˆÒh"Êós×u,o7neC>Tm¤]\¯ò€« \z¯ÆN.ØïMN_ËÆ\ŒwbÒàº@=[`@°OÉ*£A‰%Û¢`n—¶ÄÞöÓÓÄ01ÊÍ…^™õb•eÓ”ÖÙN3ÃmïŠ)ÈùÎ ©§çΙ’¢q¹JÞºSVºãDrÃr \{óv‰¦MR <p”i «÷ ÚY=Î%À¥ƒ} ¹gh7£êò Fíâ—]š‚‚·EºµŸV-7R—.^Í:¼è×ÇVB÷ ßÞíoÌÕö›–-…ü†y¦]ë˜Ytö`)ÕŒíFÄ3+ùtuùü sW:gûi÷Ûi×󦇸ݧVÏö ½Xáƒá»siÌóSŠÔà[oÄ×fhº¡Â­ñ¾léhºÙnį|dÄ®2ö´nDp‹–^nø$Ç”¡X·êâ†=õ,6x‚†Âv¢H >"a9s¥½4é¾i öR…M¢ ìuò%IjÀŠÝ&&ö´®ç>–ÌØY–âhRgÏÙ8 8¥mrüž¬kåUbxP]×NÃÑwìÌØK.0}—¹¸aV[B°§Ö¶vc‚nÈneÒ&Ëí4,û}ÃÂ|© ùa54Ãi®€ª]¬Ú ͺfÊ^דe&Š•MŸ²P5†szíq¡`R* Ï“&[¯A©bÆÞÂNÔæòÈRò@–xpáR8°j$ïÝ)ÌTÜ‚<‡dÔÖ3”~ÁšDptö+äµ’¼™‰y•¦{¡Án+«nïeQœWã¾IÍ á½»ôÈÉØÙº I›[~`Dé]~#†\ì~y/CÊúæ9K§Öo; ˆú-ho í>’»G% uQ툙̹XÌË•õúeOqËÜKUe¢|` iæF>2Ë?+ãò›°_åíe¿¾ÝÆ|U»zfÜf¡àeÏrØËýøRkæ?æ¿™G=ÇŠG1ÙêILÞ‡‚8ņP@VjΡ 8-Y;QÂ샪÷XœäåËwêøŒ((¢äöæ™êcDÇN£@ÑNqë éÆÀ:N{Y¦ÌŸ/e̯ßX–%/ybãÉ’Ùq$/ôìòm*’9幑ìÙs3m»NÉç:0Ür}AkÖ³ljrD¤D••Ô€N"bCÐLÉc0 xÔK!`;ù+ôÁ/ád2úîXÄ âOØ«‡ºáÃ#—žS"NÛ% ]4‹ºpëi=Y–½¬°meÏYî Áq]‹’T`ªnÖh\: ÀJPt3“![ù°b!)^XöÕ0ft)Ùo§œ¨Ê°’ö &m&<¬þ„¹k5YuÞ-oÌÌËöcÝ‚A‘Vfõ^A˜š Ž”Vܾ›³ê>õiºŠLŽó†µ©¶ÏÜ%² ý‚ñŠìYÎŽ€ò€ ò˜AÖ?í_"Ë¥ ?{Ú¦T=Õ„[w ´¹=ekîêq£ä`¤j OŽBi†ÁsXt4jߚăy-eNÌx–ûÆœ-iö‰ú#æÔÚíWË££ºÞµpákù &è×Ï­nÎôóåÈÃxLL¼j~ÿÇÿú÷SÁ|²¥÷¿^˜+) /û ÖœèÿƒÇÎSüùc¢T£¼c Mjwõv?<˜8XA$wÙñwŽ.ÎN‰{ˆ»…o“øùŸOûßþõŸuÚæüOí?.κk8°rEƒ cŸMâxºQ»J4ËU¾­…˜!+sÝ`ˆ°œjyÖ3üêÌ\6\.#'ûÞd]7´‘eÓÖ­/P2‘¤îC`q"É jeº¤ ì,€ AeÚ´ab³´šO Z‚y¤iiZn;e\ò§<‚ w³õº’Dok¥ÙãG¯ ¡tX2]b‰U˜lÍ´}’_¿Òö-‰ð2¿KsWb©V™öË [2ž´^-[úåå=¬4«[¢»¤5»¬Ë؇`ñ-(@ÝÔc¦(h‰u’ª¬…mÅ)ÑôP X˜f¿mu³7:@W‚Ñ­©:uKòøÊ¾r„Aj<_–KHñZ<`®º˺<ƒø×%ŒŒv‚¡B¢æ4Ìe…Þ> ˜…BjE4\¶æ¹Ôüˆxë§CHrØ1H‡¨ à²,wc긬Á­bðª~æ¼1­X§’¥9ý⮃Y'çw»£@×q*™L×v¾1RÊüòñ-óâuž™&²¤È„ìõ× c Ž^®’lÛðëzµMüÃ8ÅFNIeÝÛ¾¤~GüOc«%hp.›P3‚»BSY„˜,&-Ejè½[θ¶Š^äcŸIô# yj÷rˆPÓ Š‡L Xw–oX]À…å»(ÚÕ¯>½óF5¦VžÍßvÕ׿ãÜ'=‡ž³X5Σ ±9ºí©Þ3å†5¯nUø)1õò‘ú]Ì=e±iâòcù!q‚]´={».é ¿oèž>©SÖAâlGÄd‹E)½Ü('‘Èl<êš<–évbša`øß©eýÆ >Á—bçÏ’¹ f6‡ã÷š=O"³€…S¨þ °•$ ¢)wúí.¸o…Óh7L…¶ùÛ)Ñ¥¡Ìâв»tCd IcÅÌcÉü“‰§’‘fêñ¨Ó܃‡]LÛ!¦^•Y¡kLbÌMÄLÈ®3ä¬*˜8_qñü†å5¿k€©Ä»é\£Sľ‚[ÊU¿b²mwRÛA¬Âܵ:*ÌwÃFˆ´ú„^¢YÏEÖcX =ãªÑì±yšÐB$_RÖ[&]kÛ9Q»zÖ®f›—î×ç®Pð"¾-ؼB*»Âµ Í”¨grÀ×&ÿk_ÎP¦¶u^¦¼3÷EJ¹øâË®|™oÝJCfº8~A±h¦8-yo«¯Áƒy­eqpÌk¹oÌÙ’³Þú3æÔK×û«åƒÑYýR‹ÃhFc‚´õ"Š[$_˜/gþ?³ö×à€½,eþÿ}—crücâ¸ýû?¨=í«·ð]6=¾Í¯¾Ö6¾Ï'"ù÷ö¾'wøÿ©a-Ã`lùwá÷±¨«´£¦£¾tÙµIÏç`Ûßáø)ÈW#áiÂ%¦Â—oYÞ•Åa3Mþî…ԛ×µMò²&©8TÂ%VÿÒg[ަ®¸LW—žŽ,ÁÛ¡°&H­ÔW´Æö5@K݈Š“~¡v_#9†Eª}—"°‹ $¹_»ÐTÀVEÿ-—ˆ„K &çQàjœw¹ÈwÄFÜÜ«¤Qj )±ÊµH³Qëµ}1†dlúr\¦q®K³ÇNz|d¿¸ÒZ(F+×tòœ!æ"W,ù—\YÑ ¹[..)hB> c\~п\)žYq©ÉÝ£9;ë>;˜_/ÌÈsjM)•ßy)¼•°÷êìEÀÿ…˜™˜[­¥X§›p)cÝjUPAZ]$Vqé«ÐÀ¡©Þº¯ã´‡ˆeÓQþ¬ùòçVŠ¥§ˆ%MŸ—CÅ—âûã|xE­½è ¦ ¦H0͆²–*ù*1<¨!ïüLðNÞ5Ìì ã85Ð ãÐrJxT¤ZÕ¤¨T@a,`b¸™€#…èûÜfÅŽu`ù>ªÆ¿ƒl‰ixh¢øÙd¢žÚ“®¬“§#/2Á'8¼0'½%oW0Bn¢ áè”ÆwÜíÁäfËvNòÿþâ©“šý Ÿv7ƒ©yÂQz/ ÆÞ ´/Ïž8ðâ—Ö[k{¨‘­I°GÁµ©Ù›zšJpRü¢oVt½éFj+aÐ*Fê.dçɸ¹hWs±¹7ãï•Õ‡HWj°w“6áÈÀ§¸‚´g¼ˆpÌšÃpS$N‹i߈g!WÀ³Ø7æÞù9–?bžZ›Ï¿ZÞ˜l/šW-Žæ_0¥fÒ%|Á|9ò°Tf³[¡Õv!”v²ÚU—z0}Ì©5º%å³te¾00¦JòÞ²$Cf*kÓQ^V)fïJ™;LyšÈ5.Õ«ú ¶lÂKÕþ3Y;ÇéšmËK5{ÜÙ&i*½ââ^³©Þž´±é„Aë´AŠwQÞ¿÷êñÈÅ*!qô]ÜɘÐYò¤­Ñå½K$ŲvûG9'ªÃ¹zÀ(ñFpPà$X›P —rÒ˜:åM!LV û&¢ëV¼ì’?¶àìU:¬Ùº!jœþ±Y}í¦¹„ø$¾ª`ÍL¿OîÇD”‡Àåè„?ŸV²éáœÎ¼WÒº|ùĦFó­—hû„× ¤“of¢©º¤YD•Ù¸{F.*½V%ŠsU4-ÕŒ] DjÝוã|‘Òf;^[»‰µiÿðKæ„n`×î;Õ03|_^¸Å%ð'Ì} îZ¿a.gpØ HòK‚რI;;Ì4ñ¶Ád÷æUëçåoG^l@Ï,…L\û9P— Õóë…IszW9 ñ„æXqÖ¥Æý7v4ŒÊj9ùWIµ ý9Š,ü¥ÈbÓÊr ˆ‚â ¼«æF!ò¼9P¦àÙhtUT€(±ÙG¹wÈÑ94d’IR>É54û*J;¸90¼¸ŽÒºð„òJyrÖ´[sjÞ¥6g_8†æù†‡CÌ Ž Ó *óBql:¾ÇÇ8†Ê'POD§J.5+šHÎÑk$Ò™7L2ÝÇ)Qúö ÖÉIX0äj^‡­©Ùú LÕF-yWò٬ö]F Á¯Nåq)k°¼`ö€’~Þ[œÌcyðhSÛ£Ù!IŸZ¢í|”lSÒ„ß1-ï\ddQëÇ#:»YD"ð‹IO^ߨæ!=•—jr¶:ðMLE¥Ýð&¤1_%`ÚÃ=*%ÆØ#¨Ãþb©Ù‡ÎÙ!XV´­ÚìË}8 ‡l½0Òy'”ÈŠ¸<‹u9œŒpñrºhű>ä—@kêÈ øÌw<Ä¡@…(XH$*IH™¤6Õ,?Lu ¦òHéììÃ%§ÿXG§Ëר[mn­ø5Òzà—®€¸ª`{Ñbsäž³Ajm󈾩i‡yqoÈø¤ÀKÆ?ŒIˆ_¿q*¸—â`ËHSHZÂþÂüzaú4æ©å@¢7!f¼0•e”™¯â’'ÑŸÊ?/KZQ^®Ø‰C™âFª4òhJ»c²u “ª8¶c ð i""„Ã2n~ïÃÏT×bv6œz•uçM öLš¹6æ G­TŸ«<™V&0*˜e¸»Ær´×®š8º» m‚:³’¹ŒËt°ð¾\ÓHVËYÙƒ$-øìpdq€w>@(û^K}I1] ËÕîÁ µ )¯‹ÅýŠI; ¢[Õ©IŠÌ¨ '”2´–Í+ñpöÅù(PgÊ„¢ä<—k*›ˆ¶ˆìŠ剻?åù+wwƒqd±“̵™±–]|.cÅ}"¶Ëü\WÓÜ9“**#y%Nå|«¾3¶Ã…)1&º¤6¼ Þ>å„£F’uƪÜá{J-9¦ï`â,p“³pó;pNÒSö7̼–CÄXw§á;^×7f¬l7%BÔH¬ùÌ]ë>‘wËßÏ:ç)‰Ìv‹@E¬¤§xŒÉõ“äÁ¤-)Á+²È0w­Ò•çf7üB`sªY•šòÓòžûÁTyŸB¹  Ý忞ÿŽ9]ý}ä‹ÂK[󺵽8U¬ËiJ!Ý¥ä Ž¤+­mÞün–*³VŠQ’°dÅràMB’¤ukMÉ0Q>:Y”G2þéHLÿ»o^a¨+{‹”õ7'ìÍk@yÚíçWòæú«,™º²Sð2hÎæ£xqÆ¿»R$›]‚„“¿"ÔH0A€:å©‹Zéyd Óæöì“iË9,³íÌ\_'i–7½Ò õý ÓA4,ù­Æ•m—a\’ç²¢øháRT+s$cÜ¥ðø`È͆í¢ã>ËNde%¢ž¦¹ìeäÎf1Xäêü^7ÜÓ~UÞ⛓Ò?ªOp.¥.Þ˜zôר¢´ÿöºÈ•Øe¥Êvû¹D÷–)ÑëyJ 0/ú° Q¸ž“(to3òUÓ(w<‰ˆÔBSÌû ¾äv#js¾K¹^¾YªÜ(…7½±ÉU'´Ž]“l®Aˇ.0òh—T%ôO! FÝ ™Ýev—È ÁU& ¬HÊNR9L°]Ç@û ñô ¢cèD)t—¨ÊU./Ù Èç×eÄmg¡qÏ{!é"‹Å)‚±½@{q«ÂÆty&F“]1ÊÞÜ–TRñCØ[Q˜'Fl#ŒâMć‹´Ö²y!ï]º†›<¶ë½5£;´¯T÷1¥7k¤t#Ñà §aW¦Æit>§#ëØË¡4‰-]Û ©ç&œ@:Âá+2—ÍSÓ÷$çßýJVƒ$}¸agÞ¤Âáý©›² ÇLêj©JÑÐЧvz(厑ìÜõ>¸Ê[÷‚Ë>¹Fîîãuò¿òñ ÌÔÚÏZ¶ ¾ÔéݘJ“ &fIª/@Ç@¢¼•á¶Ë–DPRgÈÌ®„íÖàô2v0(/·ÞƒP~:ÂS(/fÆ®1R=£dXg™±éæ²7–º#½Õ ;l^5F!÷t‰…F~IÏ öŒþ¶Gär:%×!µÌÔ¥KªåtàS”+G9tüݘª«ÁrtÕË…‘œWµëqQÐOåȱW.êå<¾ÆI_js’´ZU³(£(ÊCòÀ¨7–klL’ŸåξwuÉ©v>Ôð³Ô•èüïâ”[г´1‰qƒT˜N}s@ݬM~‹¤AмæNC"è–N•àÚëtu‰'%¯cÚ<»4ç;‘6ßQþ×¼Ç-/XÆï>5ÍåŒ*øÒ8)0JqMËže«Õ¡ªÏåYÖy@­š×÷ïÊ38íÄÒÓ“vúžZ˜#r"›Zä¾Ùqíh/0oÅþƒ!7{]eY>‰ ›Ò^ÝsØ[]Éã­›X©qêºd¼>°–ÍìAË:.Ç_˜?‹³³ßÔÖLg@FãìxËØ7¼Ã¦_˜Ë>‰y:YzRyïiô~ò>äê‰v5˜œÁ©oW6éÞy1rz•ðC¯C¨ri<ð8IŸŒª4_<W gÖ¸|"Æ´ƒ‚ú¸tr¥Á¬S6»êË>U¦?}´çìãʧåÍ1ÚÞÑ&ª ÉôÏ’§dq*±Rœ¯Gi7²ÑñÎíL¨4Sè3Ž܆ˆ$ŸÔucä…ÊT›5 rø$wN­;+^§Jd¸C€•G‰°œ ЦműS¢)òñžÅ½ßBуgÁ[ªõÍN7æf§D¶¢r?ì”è€ÔÞì”ÏÁX;ÙYe;%`´7;U„çÃ=‰ ÇlqàêÅM»í7CÅCMƒÚ µûœo†Ú!½s„»‡›nðÅMï››âÃÍ<ÜsSûá¦Js‘nʈ”ÞdsSF<Ë‹›öã¢usS" S¹¹©bIòÃM•”2½¹)‰4便¹©BN_ìtÃ/~z—Ø ÇùR†ÚóïÍPñfGa}ø%Þ}¸éßðºü,º1c§w<•H–ÖŽ:,¿¿8*ÑÕ׋¥æ\ûÃR7üb©w‰ÍR[W–J÷êo– Ù*€d3LâfäY{Ã7Û¾1—ýÈ7K%’½­‡¥ŽÒNê–ÍRG);¢Ã\uœÍU7üâªw‰Í3i3¿¸,¡6NÃÿ`²éjsUÅÓ·‡«Ž:î[Û\uXœ¿y¦BÏÇÎçú¹1íé£=,à“Ð厬¢5à"•íÕy©ªªóë…qN¿_¯Z¹8¾äÁAç ¢5;lu{—Ü»}Cñ~$YëP*íŸQc8D€l¬Xkð†T*Õå„É|Ĥ Ñ†WÜ”“÷êv„#çùm“³°Õä@9¡*§ZM  Œ= j¶†„¼´ò2¬Šh?05œõU¢;°[ªd@ª±åey×¹†’âTXß)!KÉs=ºA ìIX—Ý"%ð•\ÃÅx»¶í’É)Û£VžŒšx3¼1yÈ‘Œ\c|ë¢~Á ÓÜé^•xWŽ„—¾V/W“ë©ÀŽíÜhxe×êôÊ«”*Wké|²Ó¬GëÛ«DÕ¾«c´kZî°¹FÉþ€ãƒ*üRŠÙäíÄÅ:ÏýÜ©xª4%½UV­Š5L$ç,Q5ïöG:»K`¡zóîe‘^±½o¸®ÙïÆäb|mhýâ>Owß0ØU¥ÿ–צô}m;L?˜zùP*ð7ð.àÓæ·³®o6ð,å|¾.'¯DÿqÚ7&êM—4Þnçó Ïó æk;»m{¯±37×mCÏX TðÂä³\-ý<å«ó­Ÿ6L¹üWñJÍg57fe{²×êt‰…ìBÙ³ôhÇ<}ýý‰:h¨¥pÆçAŒÛh|Îö'B!˜lÈrP@“)­M´çñŒŸÇ?ø[åFŒX ´ñY?Müïÿòiæ?NE%)º*¡Ô9ºìC¶^±¿‘ÏG :ÞÝIÖŸÆW0™’¨kîü:ߪµäUBI[ÝãþǴ䡟U_òI޶ô)›u»0:k¢£üâå«@VªêèWnùúý^¯¡ •‡kK;=Ç¿üÚbðÆä=¼äµErê,+E#EÁå@…2¬ênœEÙ*1ê¢^CÌsrÔïÕÒ:Ê(ÒB8óÚ¿ü£ZÒÐõ-½ì——!¡¨D…I M2Á'l?Jðî\”¹ µÌ_>q¿ÕKädªÓÏçá¡ÿƒZòЋ,úR‚/æi`Øu$ÑˉoNÚÛ…¯;,})l` Þ†Ö¯•”6é] ƒ÷°ÿ!í8ˆ>¥Á2yYëÉ¡NŽÚQ “¢ç›¡F×çhLþÓßø¨x[‰OÀMI£sÉoÕ&|¬/ø?õ‰•tf¥Uйœ0ë †ýÆäyMç&â5€zIEhû$hÒìé»-2½øsw˜G»àºSYílzyØ ¨é)²)ž¥ÉDH|üÞ¬aÎ+»FÞÉ„²#ðíTÑŽ›ý —v÷a ]ÈŽ«ZŸ?aúò³/j饨Э¶Š¯“Kh«Š'P.Ûñâ©3˜ý'ÌÝ÷]ë7Œ>%•¿b.E‰@F_×´@¡`Ç1¬`ÞFÛ›üΫã'—4Òòçϰ·>nX1šÉ© N H0æ[Âf•s)ˆb¥rç½p_åqc êàsÞõ~šÙÉ%OŽºRæl+%ÆN¼¶º¿õ8òfs'òá€a°A6Õ «ï%¸†DŸ¶½¦-Æ)Ût"K«`UpzÈV¦‚]Á{÷Þ äµØ]8‰jì1y™>c¬Ê‡Ï‚7ïð ö<åZÏ£n¯ÞóµRxgW÷±×2;çÆ½ÖrE¡Ï½¦YÓž|fu¨×ôÝEu*ñ{„_©Æd• í5 Ôí:Œ{ž;|ë^^IW~¯/©>Ÿµä¥%3Ô^ëÞ›q#önÝ ìݼ»¸÷û„ â㦗=‰‡ Î,ÉU8$yÖé!Ú³’7Y{¡oªÿz.TAߘÅÐ Ú=cøæÍPÌVã ªzCÌ+‹k§ìàÞ‚Õ m±8_dâñ{MWç+mèaœ‰‹É øãvÔ÷–B»¸tô½¥˜ q§°¡%K)Òô£êãKÌbnØvF¼'v½B¤T´YÄÓ èòçÖ)=}××%ô]'ýÓŽ“Z‘¡ooV–—Æ`KzÈŒ¿];fÃ557aZ£Ñª¿òV0mqñ¸xø¢vi÷I'ÔÐ,Ôæ=ìj@Al…ás¢ë s+úžÖx•Pµ[h‚¥¤Uks 1›0HžÍ]®¿­Ú®¬Dõæ1_fU! B°*Y_Ë­ÂÔ“ñ´°Õ± §,ëY¬hjR ˆCÊÒÓÐÚl9¤piˆô l:Y2ÊwlÅ)j¼O±–w— òC=nɶ„®Y6ô6×V£‰oÕßí±öƾÔŒ°n‹âÆØ}ºZr&9¾ŠÒ¡ ^¶f“g‡å±&¥š…©ÍÛ¤Yc¾–ÇÓ¬³54bù]éô]R ÛZͯ²æUʬ†—†\†¿ºîxF¬´cæž³wÙuú;P(¢wÞ’š…fôâpÆd}sø˜âw†fI¼yìP8}!YvSêi%Ó@&®"Ô$/Ù©o‡ˆuíôÊÕ39óÇIŠucb½ëI¨¼œüÙ‘ïŽ(En6á*vÚž%„W*¶RB+|[Y§oòV.>œ;>`íRƙȞ*˶¨¼?\à>ôª–š¢³Êu‰µÔíúvUØO¿X÷á.Ñ0Pÿ ¯Jãµìæ$ §ˆÁGýxÛÔ­g2Üäºì=~`-Ú|ý\LŸ©8ç.ß«QñzòˆñeµvJ²Ì'oVuZ}ÂúÀÃãƒX—³K_ͯ ±Xçék´‘€"•DƳX$R‹ó‚/íìµb—¥{c !܆åS.}"ÕTj¦pùë)¢S4”IGO7ýzƒÇ¤ÿ`l.'*C.'ÉÙHñ÷Ò™úfÒ„¡k–I1ûo*É'û=|úDbV:vdf±n„6},7©]HŽ<µï[ïB„.Ÿ!u; D”VË>!W! ë Ê¥Lí sœY«ý‰göG%¯¤[M‹•éJÕ²dó«éë6j?·}gìXØÍ­5‡Ú÷ÇÊ.'nx³wÛ¹þâzà=‡QnŒö1„&s}Á-;âï…)›¢¬ìÁ€¨­Yͧ¤4 ËÉ[už0qcÕèÙ¢Ê —s®nÌþÖê,ÏÙÿÊà¥ÿõÇÿªôendstream endobj 6 0 obj 13760 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T12:10:05+10:00 2013-08-12T12:10:05+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/relative_central.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000014065 00000 n 0000015748 00000 n 0000014006 00000 n 0000013866 00000 n 0000000015 00000 n 0000013845 00000 n 0000014129 00000 n 0000014170 00000 n 0000014199 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<3A675C24019183FD34D2560CCD518056><3A675C24019183FD34D2560CCD518056>] >> startxref 15995 %%EOF opengv/doc/addons/images/nonoverlapping.pdf0000664016516101651610000002641413344612246020034 0ustar dimadima%PDF-1.4 %Çì¢ 5 0 obj <> stream xœÝ¹’dÉržõ~Š”)$b_ž2AF©i#ô$¼>þï÷8'³ªÚ®Ô ÊFèqÏØÃw÷8õ陉ÿο?ÿþñ/ÿ6ÿñÿüû£çØåñ¿…þ??ÊzÖ6ÿùíÿö¯?Z¯Y½JOùñ÷Ñ[}îúh;?kyüúñ¿~¬V×3Gis?W£Ñhý™¦ÕgKã´bèõh3ÏçöP3ÍgÉ‘Õ,i.¡h¤9—§Û,YMÖsn·é³–g.:ryî©F¹Tݵ€áiiµgíÏÖµÏùœ§UÕrÔji?Ë­¦€çöXóÙXT¯ûÙS{´ÑšÓ¨––Yg=Z¨ËÒGÑvcMÿ~N/=G»Wιô¦Vé¹[æ t’µ­xk í®0Tgç]ˆ’Ÿ±îª­?k}Ô™ò³o5ÒªuÔÑI?ü¢IyNaÔý¹âà4—ºep4ÖУtÝd Ýiä&›mhÒTÝ-¿]òäP|ð“iuÌCktßÀzkþÿþãG_EÓm‘N/ÏÔܼígjž3ôñë7ô1'¦µé–…øÇÿøS#ýõõžJÊ&Ç– ÂØÙwÖ²îNO+ÑGÓøk§’ÔT¤ßRnÏÙcÕdœ¿‚˜½IóâÜuïÓ4QׄÌM¦¹_f‹›_왞4*gø¯ÝÆÞ ÅΕ“õÂÿÐH] ]z0ôàÄg] žë#5îËK¯Éãö!º6aÍÖ'„܇8tsX_ûéÂû³sãe…ÿ‰qbÙ¢ô:‘Vâc®nö5ž©çô¥Ûâo éÜöYøŸé¯K¦õŽL[p°dšÈkp{iŽg;T£}w †½ºØH‹4×—}‡å‚Ù8àŸqðu¼µ¨åÀ-¦@¹G}–X“ÏÛê9®?vŸ$mS»ï_kœÈÚ·ûß²g«²HCˆ5 9«eAÂ…õÛ¼@ï©Û¼¾~±j^>“mNÞrè{È.|÷ë¼/Æå@ñãóUZA/~3™K.p»7¢r¢ZõŠØÅoî"Ķ®ƒ@ïDÉ3K1é®éÐÔ5ÏW Lá«ExÿsMõqýo«Û£"ÈÙ:cÜÖ‡Tèƽöôs÷¾Î"ä" R<¾·­Ð<±( —ж :)¬“nÀ#Ęn«t8Œƒ"Ø\*xWÃ’B;¬Ö¼§­VÉ)ÉÎ\JbZˆÎhx¼Yƒ„A‚iÈàé5‰8²aQá¾a÷€dß[ŒkÒÄìªÌ奯™C—Fš˜ß¥ŒR» "Alî¿`¿^±4Q,ƪÛ$v 8šKEiK¥³¼ˆŠ€¥4†—7NLumXgÅ€2Æ‹3l•gù›¶¹es œô:ûuh…«HÝ'²Ø —5¼"½7ìD¥Þ[¤3Bc®ðukëôp Qÿ¦˜b@^AHþy^»sZt9[tï3 äÓ[>°ÔK^zä ¦8&Ö‘[„º^˜ ‚H;Îþ âÕ'ç£ÜãL íW/“è ùˆ8ZŽ^húO˜wvöú¤Ä›"!öÂlg¨ËÐcÜä<0c¢š5¢­…‘É3ãwß4)¬prÿjóÞ=¤ÁHþWÓ«: ÛÖ¡ç’ KÑ/S·à9ÄË gcç: ×~ÃAÀùí÷¼Ï¯ÿAèµrˆ·Å|çæ÷µžÑ_7_Û¸Ös0L»ÏÉ.‡eK²¥è£E}®³À|±#çïß ,.[¤ø@ª¥hÁ[ç-±8블sIÒ˜qÈ®1b#u/³˜¿…ìn5ƒ)мì›ýr ÿ¼Û×é}œ1ß0çêâÅKO9¤þ žÆlK¬‚ù[Æ‹ýй§úÇm®NñbCUeâ㈣E´lé|$Ú$K$,+ðBø.Ü,’[‹óúÈ(jA`lðɤ›$ÂWGwÚ™H ›–ºÍ=öP– ÎÄõ–´ˆD J \']{Æä*©$½"xc†äJbaß°z­K/ l:–GÈÖ’èÐÁ¢d¤ML²Ì2t…É>I­1w¢„+Ü7ŒIA¼0d*îbo²\&i¯Qô‚t,Þî`¦…Œ6¶ó¹Héâ˜cãÔÕ~NG'ŒÝâ +WfXîè1ëAÍu059Liašƒ¬d„¸GlÕn˜#í\Û«–7GŠaÌ!e›cª+nÍy@ö F“r.ڱܨ§Á‘“¿òð£V‰:k¥•h E2{,Á²02¢I¯K°èôwÈV‚EäI|C.Ió{,Ñlj Üm3E³\[åÐæ8nˆ=9‘w¯4È1£ |€«Ãk7¢_É\NjrQâ…´?`pclúiãrÀ‹¹zIº¯Ìß#ߘ%k"#. Ò™!Jä×ú€‘¬w^E¢uÒ>˜Ï\­б`Zq]dØnÄØ6 Ivò¹áûæfo»MâDæÀF5G³й¡ïÉ‘£Œ4¥ÂcQ˜a‚—É,ãÌb陆ϒ…FŠ×Ié­bwÉÁRµØÁ“m!ÁsÈ…±_ðO¼Ì‡W 2€OæÏ “ÇÒÑnH’ň1›ïG^p…îëÆ/óȱ9.Žm…+¯,›¡á‹iKŒeV¨áÀlLŠœ,ÄÕBGƒÑonÇ€•=0ÌýÛu7â‹ãƽæ~ÎuÛ)O׉rªˆc ¢UdXÞ0pÅ£èê=H½/ÊBR˲ѡ•ÀÒvVÆ1¡J쌲ÂnC#”qZÂc2oÅ¡u¾&;SõCÈ€ä{Õ?±sÙ:T•x÷¤‡Ä§z”À3\Ñ/­¾9°ä,’p¶W ¢+Þ—Fo[ ƈt¥‡D4 &•¾k‘Û›(¤¡Ÿq¡°-÷ã˜e«qRNcÓg"¿_˜~ÉK…¹ÌêØR>‰áclÍ€±•ˆâDJ‰•ÎítU Ëœë8­ðÏéfï3¦P¾FÄc3–4'öº–Ç«¬€’¬¦,a˜!dnÀD‹ ç¸aõ‡[v]-PßÖÌ1ÜW‹ä|?T¢SËv¤«´·%ÒËP½$ =Ä϶ Š´]5eSwûä0dgH(³ºƒ¨g0$)ã¢"ûu ³´½ÜSH‚7Ì@‘2Â(VFˆ˜’'ÂBíZ”_° ¯z™öOΡ5æŒX ÛLŽm×3£¤€Ž£ì“4L!ͰöCw-GÆŠDOY;äˆÌ¯"Ѭ!xæsݲ^Áœù ƒ‘e±ÐÖ¶Z¨ˆ×<;Ê5ÄìÖ€ÛÔβ-k¦dc›Þx 9@œ·ÇΛe6ÿ¼àÒ¯û»0Ü\®9¸ajR*×C)ÒªOÎ4aû§¹J91X¦MƈB‚5×öÑC”¹-Ó‡® ›øÕt¹‘ ȼîó=lŒA†;Ë(šðe6©;Ë :¬sWj€ÒiÁ „ë9Z[x¾ÂÙB锈è&}rø—Ò“kjÁáÒ†½ÆªWpxË-`í¿È^ 3Q~W¬j`g­Ø÷–)V‘,/So^¤^8·¨É¥“Eg:]]ù¡Áæ<ò,֥鲪 ‹%I§cls¸ôyæ®Ñc]b®€·Ksž6æ&1ÅØ»tiŒáD§ÓÂÆ°RÌXvÞ½ ì'ù|‡#\”5Žy\9ÙŸz! K›¬,Z„Z e×…¢žˆášì$G(kÓñ»‡tcz‡Læò&CUv×El!N=f_†ƒ’ ²Jvn)GÕ7P(Ÿ²áïbLV¥åns,6·¥™E“8¹±­SÂô± ñ—id3[æžnyºœêñ¹ô Ýü‡B° \®ž”="Oj„°ñ¶Rô˜'ê@®ì#5Åm< ç>›ü6ÂcÜ“ÔgÅ&T¬ƒXû!ñœLnx[ä :*\MÒÆ$0(Ö‚ùVÜ” ý„¡€Zš‹8 ¶XL*ô°rxŸÙÎâÊ^­¥·ï>ÃVWr%aCN¢Ø5¼-fÛè-̈Óc8Lôjá f8ŨM¥im<Ö¥ŸfÕy妪CI6—nXxŽ“2Ʊ»2"€WJD®¸‡“RY„]".Ÿíce2ÓkèáøÚ'Å»Ðb8ÂHI§xó Þ:“Ú—P>𼼂ñ“Ý­Å®‹Ã†( Ò_½CØ6o'çZ#î íKxÖ×ïÅú%¯xP&–“¥v_\:BöÊn*ð´,ñD¤Ó1¦C0EEò¸Å˜:¡€ÕÓxëWhi=Ã"|ûA¶íãv[L‘«ÀêI§ËõY°”ZÆ1œáížBèªúi_íifÇ ëðJ\öÁ´ã•‘F+¡5sšë SH²wgzZqHú3â­OCˆ•÷q»0EšNiY²Ö½Þ1"6¢×vÆûæ±qˆí‰½bqþýÂd’âÜÿpR™H$¶Ý @ÝL0­¸«*õ£J¡;¾×Q&7NPð¶Ž¥}³§lj‚l®€A¯ÈœÎøühåÈsSÇÞƒ1Y¤9¿öû8,ö š„‹åçÝ Ê ÐûR.GYq-[h"Y§ú˜’[±|Ã0ÀØý¾|Ì€XÒAäNRüåp;)r ¸1[Ò‹+u?†½­/õjÑVx2”,TÃÖÈP},“³§sÚêºî*O/æóeF• æEy`¦´óŽ£[Ñ_˜_7†Ìk®‘ŽÅ“ÃÇp6QÿŠ1PÒÕ¢k’ ï9G6[ô$ed†J¤ …‡š´b lF!Ú9)Íf)¤9ЩÁk’»èÜN´7BŒ/H#Jâˆl¡Èÿ ½ízcÖ»*žA¶‹±¨Š¨¾\o^¦ÌâÌ2"MuÔ³>)`vQ±ì ËdOõ.»³Rp–úVmOòA¶.…  -° n1.‡È3%?:Ñi8¨wÁ>¹o-2 xÅ /„0p;IkJ4–1‰zBÅñJ¬=®ÈQ6§ƒí±¢ÐKäNu&RóΩã€jGØæûNÓ“ð3ü´ú!vï Ôž¬v»t'‰Bu q8GP™™/òÕµàNc#HRxP´sNŽ®˜ð`ûöý!<ñ ?BR>ØOÈûØ.bºàCFذW |! R6h"jpÈ$BŸ¡Ýðtkíðñûíé6 £ †>Bó\YÒ®Ûi‘À´ìbR•SÙ¯zò„✃Ì/¨˜„àº#qÖæ¹“(ÖAuä­˜9D ‘. _Ä,Au”Sª{™§zyA Äü‚aÈí¸.åÀ¢mN,ŽÞô(;†X7QW_EcÔõPç|U~à‹ájYˆDÌ.Q[tÓ…ùõETýúç•Ô.4ë¸& гŸ}Ü•I†¸Ú£ÎÒ²^ÑãH·øjÁ»“»ûÎðÙFˆøMõ§wÛ6ׯá躦¿~¾Övõþ´z‹ëo¶#—B~Ã=¥ëÑ\Ë@ðŠƒ\úõ…Éö^O‚ƒw.Õ«»D•oËñTBˆ­‡kÍê®ñv毈?½0Û=œ†lƒ¶9QßWÔd4§ò…虪‰F²».ÑaúÓÓa9ÿøj±ü6ICžrÛAÁ=<-ï3†,U×}Ø ä×ÍŸ‹ŽŒCõp¹hñæ‚´Ï1Ü|’0wÚ{‹å‡Ÿ~=IŠœ¸JÊôlœ6T¬ˆWDë ?Yws¨ä ‰Râé]à=ZRÞNS5Š ¸®Å3S­3wà·Ÿ·tpmªž¹‡$åÿxX”Ž|–_(¡F]J©!s\»Þ\g²nŒQò>" Æ#îægó'¸J…Åûá§ÍÄ ~([{µNàFf~‡SX•Í™®$Í(ð܉Œ|âÒ%ê–;<ºÞØ5‹Âgc„h$ØG ¯¼-€Ê›òᆩ£Éo4PǹÑfK¹U<ÆãÖ¹cŠâGq²Îñö+¿ù¦º1S;Q£ÖAš•’^x¯|êÄ[Ò^‰”x÷Äž'B ‡Y#©”Ýo˜c‹Dü«Esqµ`—åéÂ]q$øÛ©°«<ž$‹äÂ#tr¶Ïú—Èi½0É ŒFeŽÁŽª5‡ª× Óã`p9·¢ª¿AÐÇ2*5ï50-jÛ öD•Y>»ïçQÆ@ÏQöSÉšX‡ø¥e¥x£-ÓC:§:b…ZšÎŽ=¬…üó¼;,ß.ë¶ÞJ1@¶Ú(AMÙ ÅW*ÁsE̸Q n«ûûy@Å«œùÒ­VJeù¶\õÉmÕcPÇÏŒñâ“¥4‡Q#ÝJ¼ ­d'ÈâRKåSéWºG7ƒãG¹âsy‘“â»ÖÑbÖ{%ûá­Èt™ZdWHpUèœÊÒD»‚ ‰ùr¨O—ßý‘·|€çaŒÆ·ÃjŽr4J5ûÑZ-¶]#R¿‡»W}¤Ög¹+5׈­Àþ~Ã*‡Á9Ôv¦àf\ EÊçw{L€– øvëaïÍu ½n >á¤gs.t…E\âèv:¶üÌíñ@Ô'ñhŽ~ñV°8‚½p\™ÙF™$)Þ5ü°ç¾K? ™Ï·m]×ã3í„þ~Ãt[vð¶“û$ tA sù5mkÎÉ¿d×óÝÜpLAƒ±_N3‚³¦ýžâ€êp­ájp­ñàÓ.üùí3 ßr‹ç)ü·Ý×—íc(‡Âùlò`²¿ÓxTê¯õlq¤ñ ’Ìö.;‚ýÕ"â¦÷7sx—C-=Î~Ë7^s˜mžU\-îUž>íã¢Ò|¨ô›nòÐé7Þ]æùgsùp|Iˆli®Žó—.»3qNa,–eç+.|"hÙT ðg|ã¨ß?“ÿÄo¼z_ðüç¦ûÓAîšÍÙDõ!)L]ö¦ªbÌߣ"GÆ´Ó5ë|þª8÷ju·éö/ü<>JA )PŒ=ì:¾zÝMÎÈñ­¾xÓæ¯ù£UÂ8bVF8ÕnÕûp¸•øX_t“ß#HøK ¡£Åègì("-xcßc£Z(]`‹2™£ÍŠ5Ýaô•"}i¯Ç!§7L%f±“õX{ú•Bš+ÂIéTS-âžÃæ½¥Î"`¸Q®,î ÞQMõÂÇ W:WJ­HòS<{ .]XþV ÷nw•ü5¢õÙ°}ùÒaûÉ÷«Áîõ¤;?-ÙNîˆðÛ¢Ðæ„Åy÷F„AYÎ $—m»ñ…±êÎÕ‡æ×ˆšn[ÈòôÝêÚ pxixOZqø·«;£,8üúåG©‹0¬ƒ‡.RY‰`-^_믶[xyÊîí³Íî àJ)b¦§ÊqòÕ¹:oøçaêûÏ9Qñ̓,Ø™ëf"&O„˜Ø¶Wæ^·"Z:¶;à^²ƒfí"Øù×+˜>ùþ‚¦nGç˜Ì™Ž6û ޳Bë”»õ+RTÕüíI"—%ˆNJ+ùYϼâÉÆ “mŠ,*‚ßü©e¸­òù$IÙ‚'Þ-ÞŽ#¹>H53wàóò7Rþ~av¼ÚZF·(V+G‰ÌG`ß-8ç ¬+dR>òy >K[´Ëå Hg×¼-žØ.çXóeSÍb3/‚NyŒI^&àÌ“®VCˆJv CDz52'º×½½àÙÏsÂÆAvûréÀ òêj3>_c‰’ìlÌ(Üí,ó¸KŒTWZ7LˆÆß-üŹ|%âý^dë—œsº‹Ê-ZÔ‘ƒs‘ÖŽ˜ûùC\hädy_ —Ügþ|áÖt|$!,H‹Çæ£Æ•×Q,¾râKßÎ/¾qBrív#ß$¡Fí.†ÐÍDh4QĦ•Öó®:•óY'aZÔKF°ëCÜ£2ÂŽb•…ÑêÁ‡d›¿ÖWÂGdy<Áœ(»œãUé “ü jùû€÷ô~®}\;ÿùå,üŸçÜÏ“4|ߦºä`ñöÁOE(¥×BÖùZ¦AÖÑíkÝ¿G ëÝý†c: Ò§ÿ /ôžàÀêp­àjq­ð ði  ßrþ¬ôwÝØZÐÏþþ±,¤¯‹_˜ä7œ«ãùù¸ÂB+ðW,è-Ú'|5ˆ/õÝÜp=Ÿ@xa†Ë…îø ,ªûLq@öxÖp5¸×xø´‹‰…ïºÅC ßvoŸ“ ›/p Ý^1µ Ó§K´7–5j½7µ|ñ~þØ|úÁbáú9EÍâÕý‚Ïô¸0ÕÊ=ÂùK1ÁÔüšÿúù^ñéþi¿Ë2|Ç]Ægî¿ç¾î<Ĭ3i÷oÌYᤖŒÚß³ƒé÷¡ãmÓï)÷«E‰/²Ü#\ð½„&yp6qÏqoó^ÅÝâZ÷áÓ>>d%¾ï&ÿòŸµøÎ»ãïÉhçU ÐI8ï¾â‹®Lwu¾Ãa”tù sí ÔéŒùãI¸›n§ °Æy™s¿ððu¸……î²´ˆ¡ø ü©¡üâ€7‡;*ŠöºþÀVÐÁŒ~*ùžŸ–øD_@8/“sêTŒ®¯^³áé¯ò‚r[—('„þæUÔ”ž'Ñðó$;­xRÈÛîZ»½ØÑü5»Æ‡Ä«ŸΘ±¹ ê÷SrucøKÝ/fø?'k¾bÖŒ²\¿Æå->/fÏa‹Ÿ^ûÏíóÑX¿ý æ­×öwˇ¹g¿{}Áˆþ9…wL[´‰ÏÓr5TšÆóÒ6Nu×ã¼ýˆsãJ_žt1O—ÌWã†éß}µX.Q5Ì{,JºGàÓqç£Ù;&àmSæ†çy‚=Ý¿=Ï;ò “WdÀü¦„ž>=F1¹Œ3¦X5¾ï¥x{NuÖf¼ãÆÿ¥žÐo9©–ëA‘çEýŒk#{釸þ?&áxåÒ£àØÏ¬ãär,B˜ê÷¤#¸˜à— èÿçÿÞùþendstream endobj 6 0 obj 8947 endobj 4 0 obj <> /Contents 5 0 R >> endobj 3 0 obj << /Type /Pages /Kids [ 4 0 R ] /Count 1 >> endobj 1 0 obj <> endobj 7 0 obj <>endobj 8 0 obj <> endobj 9 0 obj <>stream 2013-08-12T17:42:02+10:00 2013-08-12T17:42:02+10:00 Dia v0.97.2 /home/laurent/ldevel/geometric_vision/doc/addons/images/nonoverlapping.dialaurent endstream endobj 2 0 obj <>endobj xref 0 10 0000000000 65535 f 0000009252 00000 n 0000010933 00000 n 0000009193 00000 n 0000009052 00000 n 0000000015 00000 n 0000009032 00000 n 0000009316 00000 n 0000009357 00000 n 0000009386 00000 n trailer << /Size 10 /Root 1 0 R /Info 2 0 R /ID [<7C54933B2BFAD043801F66C3634275F5><7C54933B2BFAD043801F66C3634275F5>] >> startxref 11178 %%EOF opengv/doc/addons/images/triangulation_noncentral.png0000664016516101651610000007164313344612246022115 0ustar dimadima‰PNG  IHDRßK•ZbKGDÿÿÿ ½§“ IDATxœìÝy\Ìùð÷]Ó}Ò’¤[b•¹’+¹ïcvñ³Øe]kY÷¹®X"w¹"ÉÊQ„Šˆî"]š®¹g¾¿?¦MÒÝÌ|‹÷óá™ï|WÖ¾ûÌçûù~>‚ !„P;C%;B¡z`uF¡ö«3BµGXBA¹¹¹d§<:ÙB¨õÊÊʬ­­9Nii)F#;Ž$auFu`êêê ,°³³‰D_Xu¦àˆ:„j‡°íŒj®^½z÷îÝ„„„œœœÒÒÒÒÒR999MMM›þýûO™2ÅÔÔ´Þ_¿~½víZ•={öÈ8³TaÛ!Ô.XYY¥§§•J511a0iii<Oü©¼¼üŠ+V®\ùù¹¹¹&&&šššÅÅÅTê—3ÒáËùIB_€iÓ¦fff¾xñ¢¨¨húôéâí<oÕªU¿ÿþûç‡tîÜùÈ‘#wïÞ¥P(2Í*eØvFµ â¶óãÇœœj6òùü.]ºdee‰ß*((deeQ¶°íŒj/”••íííko‘““6lXÍ[.—{õêÕÏ|øðaïÞ½'Ož,õˆ2„wBí‚¥¥¥››^·(YXXÔ~+î›®CCC#...??_Šù¤æþýû®®®ŸÿàXBíBddd½Ûåååk¿år¹ŸïÓµk×Û·o»ººJ%™ðx¼èèh//¯»wïVUUy{{×Ù{6BÕ~úé'ÊgNž<9uêT[[[uuu999>}úlܸ±²²²Îá±±±ŸÞ¸Ç7™ª   ö[ccãÏ÷¡P(žžžJJJåååmù66›œœ çÏŸ2dÈo¿ýþþþ5CSjÃꌪöÃ?lß¾ÝÐаöÆÉ“'§¥¥¹¹¹Mš4ISS³¤¤äÁƒÿûßÿlllRRRd***ªö[OOÏzw‹ˆˆÐÑÑ ”A¤–ðæÍƒ#F1bĈo¾ùføðáA˜››×î[¯c6BŸèÛ·ï½{÷jÞFFF4Hü://ÏÁÁ¡¸¸XüÖÂÂâùóçJJJâ·ÙÙÙ{÷îmѵ,XЩS§Fv8zôèŒ3jÞöïß?&&¦Þ=Ÿ>}êèèèèè˜Ð¢ R%f̘qãÆÌÌL%%%SSS==½+W®èëë7}0BµxxxÔ.<¨ýéºuëjºmÛ6id …÷îÝ«ì,¦­­ýúõë†IIIB¡PyZêÚµkÙÙÙAôîÝ®_¿NDEEEóO‚=¡ðõõ­ý644Tâ—xñâ…ŽŽŽ‡‡ÇÑ£Gk6vëÖ-&&ÆÚÚº¡£h4š‡Ã©iÚË—˽xñ¢¸·çÈ‘#§N:wîìÞ½;##cðàÁ ¢¢ÒübuFµ€Mí±_OŸ>wªJ±±qii©øµœœÜ€Ž9’œœÜ£GÆ ÑÔÔ\µj•dó4ŽÃáäååÀªU«Fõ÷ßÀwß}÷Çøùù€£££¹¹y+ÎŒ#êB-@£Ñ Äõx<^vv¶¥¥¥/¡®®nff–••¥§§—žžÞüö¦µµµH$b2™ Ó¸ÈÈHÿž;wnìØ±·oßîÖ­xzz6t÷²ù°:#„Z¦æ6 XÍ ¶ØØØ~ýúµèT=rvvþ|»½½}VV–••U‹ºÜÜÜJKK[tH+¼}û600°¤¤$&&¦G•••A¸¸¸ÄÇÇKðBسj™:“Ü×;V·zöì Ÿ=%Ø$¦¬¬œ’’’™™)ÙŸ/~}èСڵrÍš5VVV’½Üç#@ê2´}ûöutt¬w*;¨ªªº~ýºøÅ¤I“V­ZUZZÚ³gÏýû÷'$$P©Tyyy“Ö…—,œ !ô‰:³ N×ÔÔ5ðÑéô_ýuÅŠÒЯ_¿ØØXñkyyùÄÄDñ#m!M£ÑÌÌÌrss_¾|Ù­[·àà`33³™3gJ¼ë\"°íŒjÌøñã{õê%‰*++ÕÔÔlll¥TšàôéÓ~~~jjjvvv/^lEiÎÈÈ8tèPͧ‹-244¼yó&•J>|ø€ÄOÐlÛ¶-88¸}–fÀ»‚¡Æ­X±¢É .$ËÈÈèÂ… m9î]»¶nÝÚ¥K—¥K—Μ9SKKK<ƒÝСC÷ìÙ#©œÒ†=¡OÔéÙHHHptt$1OóUTT\¼x‘B¡èêêþúë¯qqq¼yófII‰H$’å`8‰À¶3B¨15·Û­²²²¤¤¤~ýúÅÇÇO:µk×®¯^½rss;}úôÈ‘#@[[›ìŒ­Õ!Ô˜vûõºªªJYY9??ßÂÂBQQ±  ÀÓÓs̘1^^^ 111##£¨¨HzOZKVg„PCD@@@xxxff¦¡¡¡­­­ªªj~~¾©©éÙ³gÅû„……íÙ³GCCÃÎÎŽÜ´­†c6BéS§|||ž>}* ccc9Α#GàáÇ·oß655­½ó˜1cV­Z%^‘¤ƒ¢‰—ìF¡äää-[¶DFFr8œšÙÙÙ¹¹¹***uÖê–¢¢¢S§Nq8œÎ;ÿý÷ß'OžÔÒÒòôô¼}ûvZZZBB‚§§§‰‰‰H$JOO§R©ŠŠŠâÍÍͽ¼¼HÉ,1RXð!Ô!-]º´¡B1kÖ,Y&)..NII!B<é]@@AÏž=Û³gÏÛ·o ‚‰Dßÿ=0ŒqãÆÕŒY¶··¿qã†ø$!!!~~~III²L.AXBíŸÏ'âÖ­[t:ÝÃà ˆÌÌÌAƒ…††~¾sM®ƒB¡ìß¿Ÿ ˆ™3gÀ–-[düSH ÞD‘¯¸¸xâĉ™™™¯_¿vuue0|>ßÌÌ,22²ÞC(JçÎ?ßNÄâÅ‹G=yòäÞ½{:TÊÙ¥ŸFA‘æÐ¡C'OžTRR211),,Ϫ!-×äáÏž=«÷£þùgÒ¤I’Î+S8f!$SÅÅÅGŽy÷î>|øÒ¥K—/_¦P(aaaùùùâY5šSš ##£¡ÒÒÒàÏ?ÿìÛ·ï›7o$”]¦°:#„d!???77~üñÇ™3g†††ÀâÅ‹<èíí îîîâUHš¯f„FC=yòäÞ½{ÑÑÑmŠN¬Î!)°oß¾Î;oÚ´ Æïíí-n#=zÖ¬Yššš­;¹““SC¹¸¸@ppðµk×&NœØºó“ «3BH*ž?îéééïï...rrrâaÔ£FºqãÆ°aÃÚ~‰   †>ßKtssóññQUUmûµd«3BHbØlöÞ½{çÌ™ÚÚÚwïÞŽŽær¹NNNEEEÿý·d/7xðà?ÿü“Nÿd왡¡!FÛ´iÓ²eË`öìÙúúúYYY’½´ à˜ „P[ž?~Μ9@__¿¬¬,==ÝÂÂâæÍ›®®®êêêR½úãÇ÷ìÙ“’’¢¦¦æéé¹pለˆÉ“'óùüï¿ÿþíÛ·—.]:yòä„ ¤Câ°:#„Z)??_MMMYYÙÆÆæÕ«WÑÑÑ^^^;wîÔÐÐðóó#·?áòåËcÇŽår¹þþþëÖ­“øú‡2€ól „ZãçŸö÷÷ïÒ¥‹½½=“ÉTUUõôôìܹ³›››½½½‚‚¹ñºtéâäätîܹÄÄÄ’’OOOƒAn¤–Â~g„Psݾ}ÛËËkýúõ`iiI§ÓÅý¹+V¬¸té’»»;Éù>5dÈ3gÎ(((„‡‡ëééåç瓨e°:#„STTô×_mÙ²X,VLLŒxÑ¿©S§®ZµŠì€>|xdd¤›››¢¢âË—/ÉŽÓ2ØïŒªGNNNBB¨Q£^¼xÑ£Gmmíüü|‚ Ξ=;tèP ²¶@~~¾ŽŽŽœœÙAZ«3Bè£÷ïß”——ëêêñîÝ;ÀÀÀþýûûúúv¸W[NNމ‰ Ù)Zç¨CU1bÄ•+W’’’zôè1tèP99¹ŠŠ ;v­M„B¡••UNNNIIIjõc¿3B_µ'NôíÛWüd¡¡¡’’Ò‹/àÂ… aaaæææd”Ö¹sg}}ýôôt²³´öl ôÕyûöíÙ³g­¬¬† ¶víÚ•+WΚ5ëàÁƒïß¿WQQQQQ!; ä•••Iû¡‰ÃêŒÐ×"//ïíÛ·nnn!!!Ó§OÿöÛo£¢¢²²²>|èëëÛᆷTYYYrrrß¾}ÉÒ\XúÂêéé=~üØÕÕÕÚÚ:55µ´´tΜ9“&M5jÙéd„Åbiii‰D¢>t”/xW¡/VUU•§§gjjjaa¡££c·nÝ+++555Ïž=Kv:™b0nnnPXXˆÕ!DŽ;v„„„DDD‰·<þÜÙÙ9%%…Ü`äºsçÙZÇl ô%ÈÊÊÚ°aCrr2ÄÄÄtèн{÷,Xààà@v:DïŒÉ¢¢¢zöì¹hÑ"èÛ·¯¦¦¦P(€Y³f>|K³dïܹsóæÍdi¶"Aaaá¾}û***þüóÏ„„ggç=z$''óù|‚ äååÉøÅÊÎÎ633ÓÔÔ,..¦RÛuó«3B²óòåËØØØ9sæ¼ÿÞØØ˜N§¨««ß¸qÃËË«C¯<Ò,\¸ÐÞÞ~âĉíü· Vg„¤îÍ›7@__¿¬¬ìÍ›7VVVëׯwtt8p`û<€Hÿ,’ñ>??¿K—.EGG{yyMž<™Åb‰?]¾|9¹ñ¾ZéééÛ·oWQQY¿~=ÙYÓ®»]ê Ž;fmm}üøqèÙ³§¾¾þ»wï`×®]‡¶²²";àWM(îܹóðáÃí¼ç«3B’‘••µbÅŠ½{÷—ËMKK»~ý:,[¶ìÝ»w“&M"; ªfmm½eË–sçΑ¤ ØïŒP›$%%½yóf̘1‘‘‘>>>vvvIIIL&óÙ³gýúõ£ÑhdDVg„Z#--ÍÊÊ*55µ[·nÚÚÚùùù°lÙ²!C† 8ìt¨ Ïž=[½zuçÎwìØAv–auF¨eø|¾““ÓË—/óóóutt¼½½---ׯ_¯¥¥Ev4Ô\OŸ>utt433ËÌÌ$;Kƒ°ß¡fù믿ºté’œœ,''gll¬©©ùòåK¸yóæ¾}û°4w,={özô¨wïÞùùù;w¦Ñhëׯ0`€››e$%±±±íê‘Q¬Î’°s',ZAõ[X,€ÌL03#/VÇ  ©T*tíÚõÍ›7¯^½êÚµëÌ™3ƒ‚‚´µµÉˆ¾|?üðÞ={Ö¯_/ž¿»À~ç6»v ‚‚>–æ; ª 6l 5S‡±víZ##£èèh …Ò§OŸ®]»¾ÿ>¼fÍ,ÍH6¾ýö[Ÿövc«s›­Z5ß?ÔÔà»ï@Qð›x}¾ûgÏŸÏ/,,¼}û6ìÞ½ûÕ«Wýû÷'; úêŒ=úÚµkþþþdùöl´Maá'=Ëîîpÿ>yiÚ/@ðï¿ÿr¹Ü!C†?''ÇÒÒ2>>žìh5hìØ±c…B ²³Tö^k‰ÿ+ŽýÉÆ+W€B©þó5¹sçÎôéÓ“’’ 33377÷ÆššÚÞn…#T¯ìS§àر¿ýFvjX[ëæMÈÊO6*+C×®Õ¾t|>ÿêÕ« púôéÓ§OÀ† ^½z%žHOOä”5›ðÎÐüýwˆŒ$; ŽÙh«ë×aÈo‡ ƒË—ÉK# <ïýû÷&&&›6mZºté”)SŽ;öøñãëׯ7®ëWðk }™**MMŠP ¦‚ ¹‰°íŒZàádž††â¹‡ÆŒÓ«W/ñ`8ggç+V`iFØýûÕ¥ÊËaÈ(( 5ÞDM)++[´hѳgϺwïÎb±JKK¹\®¥¥åÓ§OÉN‡„Ü»÷ÉÛìl=¢£AA¤@ØvF ¸qãÆœ9s8Žªªêµkמb³Ù—.]*((€åË—ïÖ¨!Âøñðò¥ ÓTÃêü5zóæÍ¤I“æÌ™ÖÖÖYYYàïïÿøñ ’ó!$cµn ²èt(èÙ† «ž9§¬ FŒ€âb‡Âêüµàñx.\X½z5())…†††††²Ùl77·´´´óçÏ“!òÔ´=<ò‚ƒ@ÇÐ._†’HN†½{¡Oøé'àre ŸFi›vÿ4 ‡Ã¹}û¶‡ÃÑÓÓ«ªªÊÌÌ455=r䈧§'v\ oÞ@—.S§ÂP\ ÆÆ ®%%@£‘˜ Ç;™¸\.•J•““suuMNNŽõðð TWWWQQ€3f¡öáî] RaÝ:X¶  S§Bee½²²ŠTûö%1öl|Ö­[§§§'^|ÄÇÇÇÑÑ‘Ë劷/Y²—ƒBè))pûvui€§ÊÊwêy™°:1âââÆŒó×_€ššZyyù“'O`ýúõ  ; BíÕ/¿À7ßÔÞ`;oØ””¨ö;·–HçÎAXœ=ûq£‰ ÌšݺÁ€u§¯“6›Ád2çÎáëëëààðäÉ“>|øðÁÊÊJÚú2½| Ý»‹ ©ïÞ‘˜«skUV‚ªjƒŸ††BsÆ¥]¿áá`a––`eÖÖ ¨ØäAUUU=òôô|ö왃ƒƒ¾¾þÛ·oÁÁƒ}}};wîÜ’!T—€Ï¯`04Öóç [[²bà]ÁÖRQ¶ÿbóñ[·à矫ßR(й3X[WWj++èÒ,,Äó°TUU)++WVVvêÔ‰ÃáôêÕkÒ¤INNN<OIIé‡~hk„]N.IE¥?“YxîœVç¯×ŸlÞ @“99pëÖÇh401yÉçG½?èñã®öönnnUUUïÞ½ÓÐÐøçŸȉÐÍaÁøýw³¼<3`ÏFû°tiã“­péô!Bá„ýûçÌ™#ètüµŠ4ÅÅAïÞ\ …ôt²"`un7þ÷?ظ±þŒ÷‡ úö566–m&„¾R•¥¥T--%~n®(‹wNK«>JE®^…~ýH‰Œ= ‹JJ¶lvéÍ›šcÆ´þD¯^ÁÞ½pû6deAE((€¹9ÄÄ€¾~ãÇau–>Ÿuþ<åìY¥èh媧éìÚ5ÝÅ%ÞÔt`PèêÖ3Æ=#@A°4#D:Ûyó`Û6Í/ ÕÕyçNX´šû†Æ IDAT‚ê· °XðêUõBY±±ŸüŸ^\ µ')#ñùDx81e WU•ÿa15½¾eKÓ‡ÛØ ÄåËÒŠjšàôi ÐÞ¾•Ç_½JP(5¥€Ø±ƒ bÀÈÌ$‚(,üø©ž^£q¼³$ˆD]¹gèÊ5O¼-àq·nãÏž…f> *‚¶6œ9ÞÞRŒŠj¶¼„„NÎÎl E‘áÊË·øxxü¸úµš””YY`c¯^©)€¶6|øÐ¿?ÄÄÔ>ï ¶AbbR¼½?¨¨€··Ê… j<^&…ÂYºž?W-(ÿòesK3ñcXšj?ŒœÞ2 ‚à<|Øâƒ ?–f°µ­~ ÁÌ ØìêÒ ]»V¿ølÙ{ìwn9‚(¿v-gËÛׯéyyÝ€¯£#7qâ=##Ë)SŒ@¯¥§Õ×__IgEµ‰q@>ÌHH¨3tÓê ”/ û¹nÝàÁ¬ÎmAeW¯*FD(\»¦–“ÓC¼ÑÀà…­m¦³³ÇÏ?kjkãð7„¾0,''ÆáÃYÿüc¶paËŽ¬3Ú@GE·nÕ/$RA^^ž™™Y+ŽíbcáÌ™²cÇÔ™Lñ–ªêM--ã… ,°¥RI›a!$eï­¬,Tž=#D"JC¶^"Q³vk¸g£5w ‚ÐÔÔ\µjUPPÔ5k¥+!¡àÏ?‰ðpñØ€"€WývìwwrëEÉA¥ †‡#xñ‚Þ½{³Ž …¸s8œ†Núñuj*t몪uÛÚ­»+H¡P/^ìîîž””ÔŠ3´g¬„„§#Gë냳³þéÓlv• sçò££éEEýž<¾}±4#ô• P(Z#F]Ü;Ü7oBVVݵ딕¡k×ê?µYZÂï¿WÏó^Gë†ñÙü×—““[±b‡ÃiåxÀvƒ—âïOtï^3üP¤ªJL™r{Ñ¢â·oÉN‡" sÍàeïÞ-;ìÚµc™ˆaÃZzÝVÞÔÒÒMMͲ²²µkמ;wîï¿ÿö耓B”<|¨uíœ9£þò¥ºx“ªê“"OÏ~kÖ0´´ðÝ;óÀÀ權úzÐä啼¼€rÿ¾,¯ÛÊê,îÙqbiß¾`lìzò¤-“IˆD0pàû?þ¨JKÓyð¦N¥7µ0 B5S™¨>{&³+¶²:?~ذaâ·&&&K–,!"88XX{éRIË{ù2wÝ:1BÏÎÎ'4TóÞ=àñ*ííMšT•’7o,Y¢ni)½¡¯“õŒ…â(À+lH›ÄÖFáp8¶¶¶{öìùî»ï$rάÂBÆõë»v©?zT=™BIÕÖæûùõXµ :w–ìåB¨=zÀ‹pÿ>¸»7½óõë0dÈǷÆÁåË-ºšÄÖFQTTü믿à—_~)..–ÌI«ªJ·o¿¯­M50€iÓô=RHÕÑ!¶n…¬¬®EE=þþK3BH62àÆÊ•²¹œ$W®9räСCKKKŃ [MÄf_›9ó¡®.èéi÷ùðA‘ ¸Îΰm›(-­kQ%8LL$!„š£ÔÖT›ØO$‚3gàСO6&'Ú5Ín¼JxÕ×´´4;;;÷àÁWW×›ŸÿûïƒËËoÞ„ÿæ¹GǼ´¦Og4>„’‚ª”e[[ÐÔ„ââ×:€ÊJPUmðÓÐPhÎå$¿&÷/¿ü²~ýzgg縸8j3–ÈËÌT¾{W3*ªòÔ)>_¼±ÒØ8»wo³ŸVna‰G!)25…œv|¼’‹‹´/%ùêÌb±ºwïž}èС™3g6´›€Í¦GE¥¬^mP3ùª*wÔ(ó%KZ°”5BÉÊk—._1bhx¸´¯%É~g1ƒ±iÓ&øßÿþǬ頨!¤nÞ|UG‡£© ¾¾Ý´Š44à×_áùs£òró,Í¡ö©ÊÁ´RRdp-É·Å|||"##,X°cÇ(+-½öóÏæwïº}øð±SÜÒ’˜4‰ëë«èä$ !$YÜ„gg01ìli_KZÕ9))ÉÉÉ Vúù­22"Ξ¥¼{WýY§NY}û.Y¢àè(K#„´èèÀ‡%Ožh;8HõR’ïÙãp8Št†+µÛê³g½wì¸üî›ÁÈ8Ppå de™:õyi.((R„’ 奦&<¨wV‰’JuNLL6lX%§ü=EA¨Q¾{õz4oeð` ×].K(.Y²ÄÆÆ&55UyBHR¸..`˜–&í I¾:ÇÇÇ÷ïß¿¸¸Ø]Ù…á†ålݺÍÄÄäþýûãÆëÔ©Óo¿ýV3}Ru*õÝ»w¥¥¥>>>EEE„B’b÷ý÷àÄfKûB®Î=}àÞ=é]¤ÅÕùâÅ‹£Frqq‰où¤4?þ!®Ž©üü@%=Š_”ª¼jݵºE"Ñ•+W6lØðàÁPPPèÒ¥Krr²¦¦f\\œµµu«~.„’šòrÐÒQ(…©©RºH‹{6NŸ> cÇŽ¿­Sši4Zúùúïé± ‰¤ÜzP©#FŒ¸wïÞ7|||x<^rr²¼¼|iié˜1c***Zš!„¤KM-KM*<Ú³Gz©;ô¸ql6ûòåË eܸqP«4ˆK³€Md†WÏ3€OÛå)‡¹~rZÝ«»¤ccc#""˜LfUU‹Åª¨¨(++³´´,((àr¹œœ|——_¸p¡ššÚ/¿übllœ——gllÜä¹¥;²MÜvfaÛ!ôErp`Ñhªªâ/_®óÉܹsƒƒƒ?|øàîî~ÿþýÙ³g¯[·ŽB¡üøãÐŒNgvuVÔ¢PhÀe"T¯ƒBd ÓYvv€>¢ºmÐÙ³g›››‡‡‡ß¿ßÑÑqΜ9,kúôéZZZ`bbÒä¹¥[)TPÔ¦œâ/°ùœ‘‘qæÌ™BiNƒ‚jçtüü@åÙ³:ÛÝÝÝSRRFŒŒ‰‰éÔ©ÓÖ­[óòò 9= ö;‡˜—Õ»Ýk?ÃdPõ¬÷—±ßœþ8_hgo¹uögèQÙ…BV!Á0h2L»VUUõüùóÄÄÄÄÄĤ¤¤äää²²2{{ûšÉTB_!ÂÃð|ï^óßWVV®ý‘¢¢"äææþôÓO°wï^uuuñb#Íi;7Xûme<^Ï®}COßn=^Þ ÷ÇCzÌWÐêNKÚÉa&ƒåìë™´¨ú”"íóOÛ³ÌÌ̤ÿ$&&¦§§‹>ûò²bÅ œÝ¡¯ÅÝ]@¡tãpîÞºååëûùóçÏ///7nœ¸-êlá'Ç*%lä|Ü$ËQŸ,=¥fF•S–‹_æÐÀõWEeÃzúIªH)ì0Ã6²³³ƒ‚‚bbbÄOß4¢G£G–M*„ôTVVº¸¸¼zõªñÝÔÕÕ™LfÝ­ÊÊ•”O%¥Ï9yòäÕ«Wuuu÷ü7Onn.´ý®`—y:ãcÃ°à‘ ä¹°Î>igy„:”«·4CTgjjzüøñeË–59qåÊ•T*Nç„P‡§¢¢¦T_ymÖá>>@ܽ[g{aaa`` lÙ²¥¦žôêÕËÖÖ¶­#êäÕ)–c>i,¿<üéÒSˆû»MipZ£ÿÚÎé® ªªê²eË233×­['¾Áú¹îÝ»c3B_ ;;»Ã‡^ݣпÿ˜˜¢–zÎ pw€Ø Ä‹:Õ *))ñõõ2eJÍÆ°°°çÏŸ«¨¨4©‰¦_÷ P«[5ó2¿v+8ÿ "[¤nE5ôh°‡¤Ãµk¨¨¨,_¾<33säÈ‘Ÿw.¯X±Î}IfΜ)tuuõõõïܹãéééîîÑøtOOÀI H~ò¤fã… N:¥¡¡±wïÞÖåi¢¾¨™S½>V^Rüåð_ù±L:ô)\.wùòå—.]ª³ry·nÝüýýÉJ…’’Ý»wÛÛÛõë×oÛ¶m>ôõõm¢FëèpÍÌ”œiÕcJKKøáX¿~½‘‘QëÂ4Ýúë>ó“â›z‚'äpK‰œë|9庽uˆÛΜØv~ñâ…ƒƒÃîÝ» ÆžOWÞ]±bÖÁ†  „𤍍¦ªªzöìYUUÕ´´´fÖhEooàܼ)~»dÉ’üüüo¿ývþüù­OC4Ã%ŸŠ£fÌš?¯Os ‚xqˆsÔŒù`%«ñclÑQ3æñ.LBÔœKµ'OžTUU[[Û””‚ ÌÌÌÄc=zô …dDIKhh¨¸R?{öŒ ˆÊÊÊmÛ¶ÕÌàìîî^çÖ¾}Àe99@I¡P”••322Ú£YÕùM·vu¾äSAÄÅAG͘¥¯›®S'íÊŽš19¥£<³X¬š.ü &”——‹·ûùù‰7ž}jj´ÀО:U\»Ûþ »Y£hòÐuò'cæžþÅ€nS›µ>`G™åùÌ™3ŽŽŽOž<±´´Œ:ujíO{õêË—/¯pƒú’>„˜—‰ÿœ¶áÜ¢¤¤÷áÇš}TTT‚‚‚ÒÒÒ6nܨ¥¥uÿþ}___ˆˆÚ7ßÄì8~\^^~ÿþýmÓÕÜã»NVød©VTïÆîÖhÿƒêx<Þ¼yóüýýÅ\>yòDÜ‚®ÍÁÁÁÚÚºö¸E„ЗDÍâã­~EmŠs_ûK—.=yòäó‡TTT–.]š]»F»=x0@D‹/¶³³k{žæVg%йï'-宓ä)ͶPÝv.j§mçÌÌLÈËËoÛ¶íôéÓjjjŸïfjjúÛo¿áP „¾TŠZê'Ô­hàíí]gNýÚÄ5úõë×Ë—/WUUÏÉáQÕ)—/_>vìŸÏoürïЂ¶·ÍÌÕ™*]&4«[ÚwÛùêÕ«...?677¿wï^PPPC³Q(”‰'Ê8BH–Ô,ªK¢†Usk£ª¼ÖÓUÛº&W_4Îo‘–¶vrrò´iÓlmmwïÞ]UUUïQG577¿råJ#gnAuÖ²¡ö©îr5&§¨ÝܹÙþ«Îí«íÌç󃂂†^RR2tèÐG9;;“ !D&uËê/Çâ¶sã*ߊ­åœu¯HØÀ¡kŒÕ\µò·_Þ½{æêêúæÍ›üÑÀÀ`Þ¼y©©©uŽ-..f³ÙIII ¿eýÖÝgU?™ÒøóuüwW°µß½{7pàÀ;vÐéômÛ¶]¾|Y[[›ìP!’©[V—DõFÛÎ%ÉÂYçûW¤âò«ª+]‰¢iC“——7n\\\ÜÝ»wÇÇf³8н{÷#FDEE՜᧟~š5kVee¥¯¯oC+xPBêE“ùZxip¥†5uä Ui_«9"##§L™RTTdddúÍ7ß!Ô.äÞäGÏeÀ¸ª ƒºšBÆ%ÞË#¼ÏgëƒÞôÁ¡Êu6¦¥¥íܹóàÁƒ, ƒ‚‚&L˜ ''Çáp¼¼¼>|Ø·oß[·nÉË×í+–Euæ–§ËåÕ)žÕs·M–„Bá/¿ü²iÓ&‚ |üøq]]]r#!„$¨‹:•eˆ.~[!§L™øü“b%äAÆÞ‹¿¹eé öÐö˜¯à´T±ÞÊÊÊŽ=ºyófñ²U†††sçÎ äñx...yyy3fÌÏW›,ª3p¼k™ˆ“_©ÓZÐ#"aïß¿Ÿ8qâíÛ·i4Úºuë–,Y‚Ëš ô…ɸȯwQ§ÎßÒåÕªÿ/ϽûWP{Q'­îս̄’÷rµ(]&~lÉf\â?^Ïn²ovÀFçFóx¼K—.mÞ¼9>>TTT&Nœèãã3yòd‹µ{÷îï¿ÿ¾öþ2©ÎgûTTå‹ÆÄªªt"gÖͨ¨¨I“&œîÑŒEQôDð|?t{ÑŠžU×}]Ǧ+[ffæþýûËÊÊX,‹Åb2™UUU–––ùùù,‹Çãøùùݽ{W¼¶·¬ª3¤Ü¿? 77WKKëØ±cÆ “åÕBdé>C!õüWo2/óþGˆ«4oQ§†Täˆb¾g‰`;GÁÜWîòˆJñv=§¦OURRòÇ4¾OVVÖÂ… 82l;Ëô‚ 6mÚ´bÅ @ЧOŸS§N5g\„PsDFFÞ¸qcÁ‚5“ž·7âEò¢â·âEz-ªPÑœEê%`1óYÜRÂØ‹î´L‘BƒÞô÷м¶³™™ÙÆUUU †²²²†††²²2ƒÁPSSSUU¿®½¿Œî ¦žà=\Áî ᄀ•«Þ6_iiéôéÓÃÃÃ)Ê’%KÖ®]‹½IPVV–¹¹9N?~üÒ¥K%2ãÄåßܘüñ)jE-ÊØj4yà–gz—Så(ãâTå”[2j‹€˜ïYÙ×ùjfÔaUäÕ)É¿=ŸEgP&&©5sÞ¡æ“í]Aé÷lÄÅÅ988„‡‡kjj^¸paãÆXš’,333===@pâÄ {{ûáÇ߽{—ìPuzÐ5»}¬—œDÆE¤_à y`1Z®e¥ i77û:_^•2ಸ4@go9USªNOšÄK3Ȭ:3d²öëöíÛû÷ïŸíææöôéÓ‘#GJõr}µ\\\Ä/‚¸råÊ7ß|ãáá!ž‡žÜ`µuŸùÉM¿—Gxðæ4ZÞ­‘Ŷ•C¡Aÿ] u‹e“B…ót¤2ØAFÕYQÊmç²²²1cÆs¹ÜÀÀÀ;wšJéZ!77·:[îß¿?räHKKËíÛ·³ÙlRRÕa>R¾ödm¥¯„I»¸Ì×Bwº†u Jóµðn0›ÃBE£oê~·ð“3ölÖL÷-%³ž *P€S,"¤ÐzNJJruu=þ¼ººú¹sç¶oß® @Þ#‰}šÐ133388¸[·nÛ·oohòL™iã¢NbÜRâÖl¿Š0÷•³û¾žÂBW¢è9wä¶3MÔ)"p™n>8pÀÍÍíõë×={öŒ=z´dÏú\MÏF½rrr‚ƒƒMMM7lØÐä$ôRÕ–E€Â¬Ê\‘¶Íã%íÔ²»c¦¤Ká2 v‘HQK2¿gªªª¾ûî»ãÇÀܹs·oß®¨Xÿ$!ÉÒÑÑ177ÏÌÌüü#sss777wwwGGG99©|ëo&ñ¢Nig?>™ÒüEàñFNþ=¢6Åkƒ¦(ëiydXõ¨Ì7"v!¡ÙUg{þüù¸qã^½z¥¬¬¼gÏž:+´¢¯M¡”—*$sa´ Œ®;³’0WW×:ÕyôèÑû÷ï×ÑÑ!+R½lf~¬Î-ZÔéÍi^ÊA.U¼ö++‘0Aì.)ÁRNž<éîîþêÕ«=z<~üKóW.’Có¡¯"ü®K5@ ‹‹á€ìX_ºÚÖÖÖ ãüùóááá$FªWëu*~&Œû• îë”ô¤3$£I²ìÙÀ ),kþüùâÞŒ‰'îß¿_EEE2ùss„7 IDATPÇt•?Á_:àùßsN•¨SAg‡•²ÚÃ6Ö¬Y#‰&MšôÃ?ØÙÙ5Þ+-{Ýg)äß@³Ò±Þ‹¢çV ¹Ðu²¼Õ¸ÖÌÅQÇûPKIIIí×â·¥¥¥?þøãO?ýôñ0BVžà5cƯa·ú oÞ¼qppƒ"Ál¨ƒÊâݲ ÿ÷ŸlWDR ¯IUU•øQ/+++@@DPP˜˜˜’®õlQÄðŠ£fÌë*…ü6ª²²rÁ‚â)šÔ½{w‡SûpölˆWlmÏÆéÓ§Ÿ>}jee‹½¶0EÀ¬OD£6œeÁ`ØØØ@`` F€Í›7÷ïß?''' @ è¨]K–³Kž UM¨ž»Ô¶u.(++ïØ±ãøñãFFFïI¥Rÿþûï:CeÝïÌjyÏÇ›7o^@@@EE…¿¿BB‚¸¾l\¶—ÁV&„70j–M@$ èRŸ»ÕÏÅÅEGGgÖ¬Yâ·t:ýôéÓÆÆÆÑÑÑË—/'7[ë¤â¦_àÓÏ} MÉü’5jÔ›7o–.]*þV¯ààà>}úÔÝÚ¦†{K0ßš1Ï{•·è¨ôôt'''——ß¿¿”²¡vh“0É"L²ˆÙ |KNâ&YDŸ<ÙÆBµìß¿ݺuu6>|øPAAB¡œ:uŠ”T­–w›bÉ?11±´´´öFñÒ¦{÷îUUUýüÙUgyu Mø•„€ÕtæóùAAAãÆO ñôéÓ†žE_¤ML¨jꟉ©À[pjí™/„“•R †j³±±ÑÖÖþ|û¼yófÏž]UU5jÔ(&“)û`-Å« nͪâ•ÊõZ(ù‡Ú._¾lccóÓO?UTTÔ.eAL›6mèСõ&|CÎö-?jÆ,Ï6¾[^^^¿~ý@NNnÛ¶m"Þ€ÿZ¼ák>ƒßU÷i|þçà“ýg&YÄ/%WD "²ŠXTL°ñßK;Àáp\]]`РAâí–HHÜš]uÔŒyqP¿JÂÿzÒÓÓ‡..¶=zô¸}ûvHHHMùÕÑÑid|‹L€iNçÆõë×{õêu÷îÝN:ݺu+((HÜøG_ƒDD³¡ôÓ%:•)`!Wý§Îο´aª*ÜbƒcøåCŽ6iƒÌ¸EõPPP8{ö¬žžÞ7~ÿýw²ã4æÙVNn_A“òíA]r=e•••AAA666—/_VSSÛ¶mÛÓ§O===kÛØµk—®®nƒ§ì/ŠÆEÏ«:jÆÌºZ»@ Xºt©¸ûøøÉ2j?®W}Ò^nè® jÿ¢££ét:…B9wîÙYê—Î;jÎ ±d¾‹mÛØæO…„„…B™2eJ~~~ÍG÷ïß×Þ‘#G6~’öÒvÎÏÏ8pàüA¥R7nÜxõêÕöö´>B¨¥¼¼¼þøã‚ ¦OŸþòåK²ãÔU’,¼·„ 8ÿO±+ÀÖ+%%åÛo¿6mZ^^ž««k\\ܱcÇ jvÐÒÒ•mÛ¶5~*WçúH¹yóf¯^½bbb £¢¢jZСŽnÑ¢ES§N­¨¨5jTyy9Ùq>â”1ß±„Âz¼|÷Y˜¾¢¢"((¨W¯^ÑÑÑ:::!!!<øü¡vqÏÆï¿ÿÞäš¹²­Î╹k="‰~ûí·!C†8ðÙ³gžžž²Œ„¾&ÀO%dçø*íÛ·ÏÑÑ155uÚ´iDûXÚJćÛó«*ߊthn«Ûú8AÇŽëÖ­ÛŽ;D"Q```jjêÔ©S©Ôz ¬¦¦f¿~ý›<-•Ãáüûï¿»víš>}ºµµõàÁƒëìQVVÖ½{wƒK—.€@ ¸víÚŽ;~üñÇÁƒ[XXlذ233¿ÿþ{kkkEEESSÓeË–q¹Ü:§ª3M]AAÁ AƒV¯^Mį¿þzýúu==½–ÿÍ Ô´›l¸Ë%üJF%%¥sçÎikk_¼xqÓ¦MdLj_Ã.|,dP½ö+ÓÚÖnNNNöòòš6mÚ»wïÜÝÝããã·oß.F;|øp½…»®‚‚‚Ó§O¯\¹R<¡ •J­óÔJZZšxOmmm‘H$BCCׯ__3©v||ü©S§:uê4uêÔiÓ¦ijjŠ·6¬N'wq’à¨3|XA±±±â^s}}ý¨¨¨¶wã/†4î nc&YDW§B­sãÆ F¥R¯]»Fn’ÔÜ£fÌãÝÊŠ“Û4ÔÉdŠ+§žž^HHˆd‡ÿ~³QÓÒþ÷ßëì4}útqÉçñ>·pww×Ö°°0&“)ÞþúõëšÂ]û"©™ø-==½N‚‚’’ÒØ±ck¶¡Pø¿‡ŠŠ —¿Kä+š·V¯ê%[\»kê¸z­R.Þˆâ|µ"YðËج]½BÊE°¸z+€ÑÿÀ÷7ü@’%UUÕ .¸ººž8qâÿíw\Sç÷Ç? ²·£h]€(ŠJ®o­ZWÕ¯ W«¶nQ©EEET†uÕ½E¿Ž ŽªXZÄŠ8.@†Éùýqc€°ÂJŸ÷+ÜMŸçÔ©wß4â¥J }‰!;~'F’©¼Î…ü£4yy¦w—šüÈWjJnÎP¹ß‹¸´,Ö¼ªfaii¹oß¾Q£F999Y[[÷êÕK ›FnÍ~yA¤¡Ïë»SWðl·oßž={ö½{÷ 8Ð××·U«VU#fx”/üpذagÏžmÚ´i~ýèÑ£!C†üûï¿ÜHnn®±±qFFFïÞ½¯^½*·¢@ hРAnn®ššÚ»wïòG–Š!.n•Bp:ºT=^:ìÿ\‰ü“…±IyoÍÕqµøÎ/s10Öš8f’7H€ˆ˜v®Ö8;;{yy™˜˜„……qá[UÇë+¢«v™àá‡]º{•!'ðÝ»w ,8x𠙚šúùùU©+CŽ‚6jÔ@BB‚D"áÂñ$‰ÝîÝ»eª@hh(çt1bDáÿúë/®iMÿþý‹ úÓÐÐX»v­««ëîÝ»7mÚ·xñbOOÏ)S¦899YZ‹-5˜(v3R¤*—+5Ãe/ÁçEPÜ$WPHF XkB—OŸ5±"¬NÁu @‹‡†¬yU eÍš5<¸páÂèÑ£ÿþûo¹¦M•ˆà™ø†£$èथ¸jæ\+V¬HIIÑÒÒrvv^´h‘ŽŽRŸ]•«–$‹§Xýüü¾ÿþû>}úäŸvåÊî@V/?{öìÀãñV­Z%÷—ŸÍYëúúúŽŽŽAAAkÖ¬¹}û¶ŸŸßÖ­[GŒáä䔿ÝoYQ\•+n’ãï0Ë×ãõԔؽF¡Ãƒ«–$çìHÃŽ4øI¯€vfÍ«j.|>ÿСC]ºtù矷mÛV»d§Ð•院Odf£nm¯è $$döìÙ÷ïß0tèPŸ-ZT…x%S„v’’R·nݰ°°sçÎ;wNîN;[ZZ–8,,ìÂ… lmm¹ŽS%ÃçómlllllÂÃÃ}}}>|üøñãÇwïÞÝÑÑqÔ¨Q%tâª8å6É¥ñ¢ôx²DQ=…UyC5|a‘+ãõÑ\;Óðo6Ò$0àÃBÝ´ðsA9Z„,B“:Ðe–r ¤nݺ'OžìÖ­ÛöíÛ;wî<}úôÊ]ŸÄ¸>'3㵤^{µî^ÚŠÛtÔJ+û““ãéééííýéÓ'==½U«VÍš5KCC£å)+þ‘eÏåâââfÏžíããÓ¸qc¹BBB¸…;Ⱥ»»›™™:uJ[»<·šæææ¾¾¾+W®Ü³g··wttôܹsW¯^mkkëààPX˜êI™LòT‰¼C¼h“\a=T¹‰¾Rƒš5\¯åo^%ûïKãªãôT(£ Œ?þöíÛ¿ÿþûO?ýVYÅvžäDý‘ÍWGŸmºº_—rïù×_q¥‹Lœ8ÑÓÓ³ªT*B˜ëׯsÑ-†††ÞÞÞEÞh,Y²„+{ñÿ÷²ñƒNš4©M›6—.]’e£ÈÕ®]»¶mÛ*Ò 2''çÌ™3ÞÞÞwïÞ ¡¡1vìØE‹µk×®Œß±– ˆIι\²®¦¸I^_ ÕóyçŒ÷ø+õáfŒ:<\ÎÄE!V×eRj"‘¨_¿~ׯ_ïÞ½ûÕ«We¥ Ê͇ûâ ?gˆ³Ñu•¶åø’ìßW¯^ÙÛÛhÛ¶­ŸŸ_a¯€ª( Ã¸ Å¥K—×l¦k×®wîÜpüøq.{0%%eåÊ•~~~öööžžž%Dh?zô¨mÛ¶VVVQQQŠ‹xóæÍuëÖq¢vïÞÝÙÙyèС¬tqTQbɪœ³Ç ù0Vn qº^\"]ó:¦‹©ÕôBÂ(¤¤¤N:ÅÇÇÏ›7oãÆY*ó­$px†ðYŽ×躪؛øììì5kÖ¬_¿>33ÓÀÀÀÃÃã·ß~«ø…¡) ###­­­çÏŸ¿aÆ"g§¥¥Õ«W/77·W¯^</'''99¹wïÞ¶¶¶–––%oV>íÌíïï¿sçÎÌÌLß|óÍo¿ý6iÒ$-­Êo ûEQ‚*—eqˆ9_’IÎP>ÿüóO¯^½rrröîÝ;yòäò-"ÎÁÅŸ3ÞGˆv­Óÿ€.¿˜‡0çÏŸwtt|þü9Ç›0aºuë¸xâjEí, /\¸0räÈâfrO0>üË/¿”u³Ç[YYµiÓæÑ£Gå÷ýû÷»wïöóóKHH`bb2sæL‡"Û¶3*—2 *G¯ÊMêÈR²IÎP [¶l±··×ÖÖ¾yófÇŽ˱ÂÍù™1§DúÍøCNëiñóâÅ Εammíïïß³gÏŠÊ]5ðŠŒ (Ž… z{{HLLÌŸØ­ ×ÎÙÙÙÇŽ[¿~=ç¿ÖÕÕ?~ü¼yóZ·n]‘e•ˆœ*'FRnz_B322\]]·mÛ–““Ó Aooï &(ÔЯz ¨v&¢~ø«H·mÛ¶_ýµ›U©væà\Òk×®åÌs}}ý©S§W\‰ÁMy%±JÍ ÊUxYf’+Nþd"^^^ÎÎÎzzzwîܱ²²*î\’àêÌÌ×—DF­ÔŸÔUÿœÔ¿ÿ~WW×7oÞ¨©©ÙÛÛ/_¾¼p%újŽBÚyß¾};vì¸uë÷VGGÇÆÆfÔ¨QcÆŒ)ÓfÏž=³´´lÕª—“SuH$’   ??¿Ë—/à\Ò®®®]»v­Ò}µž’Mr™Ë¥Lˆ(¨Êe‘ã…õxm5É“%pü€%Fh“/q„ˆ~þù瀀KKË;wîyîýYÿúgkó†žÑÓkÊ5gή}÷îÝýýýeŸje{*XA”¦eDDDlÚ´éèÑ£"‘€rŠ+1PQNPþWÍê/áðç31]Fy5­222¾û>üÔ©S…Ð^Š®ÍÉäñÑo¯î×=ꤧ§/]ºtëÖ­"‘ÈÄÄÄËËkâĉ57mM©Úùùóç­ZµjÙ²å³gÏ”¶)€ÄÄÄíÛ·ûûûs-µZ´háààPMŠ+1P¸(y™‘O•çÙãEVΪý%îdaL4Tƒ‹1†ëJ/-ÏŸ?ÿÏþ#V¯^½dÉ’ü§|ŒŸóIœE]\µÚLÓ8pà€‹‹KBB‚††Æ¼yó\\\Š3·k _„væÈÈÈ8|øð† ¸Ý 'Ož¼hÑ¢šR\‰Á€Òs‚”i’ÿ7O>÷í¢ º°Ò€ÀÀÀáÇ8{öìàÁƒ¹ YÉ4,##^Òr¬†þøh®Ùé€üüüJÍ[®(U;GGG·lÙ²ÜáÒ•ç’^·n]HH>WZ¸paûöíU%ƒQEÈTy^ b…ñY•°Ç+Ã$?˜×|-Ô€qúp2‚1îîîÆÆÆ¡¡¡-Z´ˆpqܧwa¹ÆíqµùÊÍÛ|sss›5k¶yóf–cΣ£ãþýû>厱ÒÀBŒ_»vˆŽŽ^Ôw‹Uì¸\^Ϊø/rî<ØÇǧeË–•õ+Έ#Μ9ÃãñbbbÌÌÌʽΗ®9ÒÒÒöìÙ³qãF®y©Å•Úµk÷òåËÛ·o±Å¦ E¨Ä¢ä< §Hpê¿ÿ±ÍXÞQgȾó^ÔÿÛ××·š¸2òÓ®]»¨¨¨Þ½{s "凔HLL sssenª8999²˜hMM͉'>zô¨ðL®¿Ž™™Ù‡”/'ƒQË%‹éßljû’š½(úÕ;žö¤ÑO'ó¡ÖIwè‚ ÒÒÒT-xÑp±"GŽ©à:_xŽRÔÕÕG}ûöí7nŒ=:77÷ÀíÚµ³±±á²Zdpââ↠Æõñb0å†óq(é…,h-Æé!°®~)úØ¿}«®¾Î½Ì qãÆéëëµ˜Š …©©©&&&?þøc—Rªv.¡ëkµ¢GOŸ>3gŽ––V```ÿþý;vì¸ÿ~.«EÖÿåÖ­[NNN*–Á¨ DåàxF‘¯Ô0Ç7Æšzhÿ9‡P[[ÛÉɉˆ¸ÓÕ¤¤$3gά„6+•`Ç+Lll,333enZA¬d£FÜÝÝe ¸ë¿¿¿ªÅd0j0¢óœcÞÒÙO$’=9==ë ¬\1âîÝ»oß¾­øRJÕÎqqqLMM•¹i¥ðéÓ§-[¶Èž kjjæ¿Â©««_¿~]Õ225•SÔìY½¢eéYNéóׯ_ [·nŠ,. ¯]»æïï?yòd ‹ÈMmÚ´1119}ú4‰D¢sçÎùúúÚÛÛ0ÀÌÌÌÓÓ“ˆbccgÍšeaa¡©©Ù¬Y3gg第¬ÂÛMžÜqE#šK„EÔ)„@ °±±á¼]% `£ƒQÔÕÕÝÜÜ,[¶Œ+ÆP*²*Ï\âE~455µµµó7a¹wï^FF7yÛ¶mrmð¾þúkî 55µ¼ß t”Úy¯†ÚÎ=1bW¤N:úúúºººšššFFFZZZÚÚÚ†††šššzzzzzz™™™ÉÉÉuëÖUµÔ_‰‰Ø°B! މ1q¢ªebT%ãÇ_·nÝ£Göïßokk[ê|###@ðúõk¹ž>}kgg'á*Þ˜?~á¦*\-b\ôHQƒû¢þñbb €‰•¡¹¹HO€”HOGn.¦L—Ê×ÖØØ888XWW×ÀÀ€•í¯žœ:…ß~Þ=8ÆŽÅ”)èÝM›ªZ2F•¡¦¦æááñÓO?­X±büøñÅ=Ê™™YDDW°!?ÞÞÞ³fÍjذ¡l„k­Âçó9—´2ýnnn^nùK§ê\Ú…á¾R“&M*eµÈHÒ×' ”—º:mÞ\)2ª)ÇŸOä DõêQe„œ2ª5‰„+«àçç§È|®(GÓ¦MóFEE™šš¦¦¦ÊFD"‘žž€Þ½{^$%%…st¨©©}üø±‚_¡j°ß¹];ìÛ‡’ë}6lˆà`ØÛ+K&FiìÜ ¯”—޾ú mÚàDZj =Â)@L ¦LAÏž˜0!o0(ññ01©êoÃP1<oÅŠV®\™ÎÝ2—H£F$$$H$ÒRx‰ÄÎÎn÷îݲi¡¡¡œÓyĈ…ù믿8Owÿþý«Ô‡Y³c6FŽ„«+·²ÜFðÝwGQÑÉ •Ñ¿?üýñÛohÛVþ#CCÂÀ99xÿOžàäI,[†¶mñý÷ˆˆ(zA77|ú¹"º<¸ÍeÔØ»wï÷ïßÿþûï¥NnР±XÌU àçç÷ý÷ßËb08®\¹Â :´ð"{öìÀãñª< êÌò¼yó@ãÆ+qM±˜† )¡abBüQ‰û0*ù_™P(ýH"¡¸8Z¿žtuó>ÕÔ¤  ùE>}"mmªS‡ÒÓ•,>£qãÆ FFFÉÉÉ%Ïôññáô^tt4…††öïß_$ÉMëÝ»7KKËÂ+„††r+L›6­²ä/Fjþ4IDATŽšm;àóqð äJokk#) §OÀ»wx÷®7dT9<LM±`ŽÍÌÎÆ„ øð¡ÀÌÇ!¢Ièé)YFF5¢G7n,y¦¬b{JJJBB‚Ýž={ä¢å„BáíÛ·ôíÛWît‰DÂU_êСƒ¿¿¥}b¨Á~gFF ‚\ûÝ;À5ðõò‚™öîU…dŒŠ1t(ZµÊ{›’"ÿ{üô >W d|¹¬ZµŠÇãùøøp%âŠÃÈȈ;ˆ‹‹5j”Oá¦Ï!!!\ÆY·nÝä>rww633;uêTÉí“*…o;s´l‰Ý»ó¼ÏÙÙ˜1ÜÏ61YYR/çºu8xYY•¾?£ªèÔ©ÀÛÏA¨RZ´€—/!æ ¾yƒ;ª^2Fu¢S§N#GŽÌÈÈX·n] Ódþf̘1}úôž={žÃÅÒë|tðàÁÕ«W[YYݼy³yóæ•$x‰Tµë$? 5jTEë{xä¹)óWzñ‚ˆèãGÒÖ&>Ÿââòª¢¿s~~û­ÀœNä' NÍšEYY$ÓéÓ4y2ef*á0ªOž<©S§Ž––Ö«W¯Š›#ó/]º´¸9ß~û-7çøñãÜHrrò¼yóÔÔÔæÌ™“‘‘Qù¢C-±9\]1x°ô81 î:§©‰áèSS<ss Žš–·øÅ!—£[8hß>ØÛ#(&&èÚ±±Øµ UÓɨvXZZþòË/YYY%„Rp+óçÏ_¹re‘ÒÒÒÂÃÃôêÕkÿþýÇ4hÐÀÕÕÕ£¢¢|}}u•éGSÚu€ˆ4lذê¶HI¡–-  ¤¤’¦ýïd`@¶¶DD·nÑÌ™QuB1Š@AÛ™3e¯1c”.(£æ§¡¡¡¦¦öäÉ“"'dffžttн;té›Ú¡ˆðì\\ ¤àóùøãù¸IFu&"S§BáòË•C£FfÍš%‘HÜÝÝËznFFƽ{÷tçT€ª©ÚE=>*.±åí[Ô¯¸8D"ØÚ" €=B¬Z6„‘ ¡®KK¬] ±XúÑ×_ãÌT¸=C|üˆðpÇÞ½ðõU¶‹/6008sæÌ?ÿüS¦/]ºÄÐU‚V-µÐ³QAttÀÌ 8yuêàÒ%ìÙƒÕ«Áã!) »váý{UKYIMEj*ÒÒò”2Ç¢EˆŽFQÕŽðp4nŒ @„_~ÁúõʶÔ¯_îܹ–-[¦øYD$KÿÓÒÒªÉÊŠ2A¾ÿ@ýúõ•¹iÅIL$ooÚ»—ˆhëVhøp"¢÷ïéÃÕŠVƒ).fC"¡= Œ·n]9ñË99Ô¿?M™R K1ò#ÓªUÔµ+eg“HDM›Ò ATZÅ‹ªE pIÛW®\QdþÞ½{ógêèèŒ;öرcU-gÉ0í\6þü“~øAZJØÕ•ÔÔhÓ&"¢‚M~¥SBDÝãǤ©Yà£Y³*aÇ' {ûJXŠAD ´i%&uéBýïDDÕ¤õ1—4Ø¥K‰Dá^ßÕŒZëw®"llpù²´”°PMMX[€7ÆçºƒŒ Ѻ5änI·nEPPE—Š Îa”›ÔT©gÏÞóæáØ1X¾çσ+†ÌùUŽƒƒCãÆCCCU-K9a~çò³a>|Fà>x€„˜™@¿~8qqª•®f³h‘ô²'ÃÖ%Ö·)ׯñŸÿÈî`”‰]»Ð°!¼¼`üx  -S5x0¿:©mmm®®®²Zû5 f;WmmipÈÇxøææHMŵkøûo|õˆÐ¹3fÌ@f¦ª­i¨«c×®7ïÞAÆž%ñö-+(×—Ht4&LÀŒЦ ²² ?þˆ‹1hj¥+ ;;;ssóÈÈÈ€€UËRªÓÅ®&ÃãIËàâÍœ= ]]Ñ•+ô÷ßDD¾¾ФIDDþI:Ñ–-ª•N(XéÊùiÿ÷”-?µå.7>бcÒØPKKèÆ "¢éÐ!Rb½Ìª‚sk4kÖ,+Y RµsJJ ###enZ IN¦3g(4”ˆhÞ<È݈hÓ&²²’ª˜Â ¨vžN;vƒYYÉ«]rq) a9¦M“ŸÙ¥ -X@§OK'DG“®.Éõ¶—H¨¦ý3*‘ˆnÞ”ÚÅ@‡yx=|¨Zé*‰DÒ±cG>>>ª–¥l0í¬b23éï¿)&†ˆhÌh×.""GG21¡£G‰ˆbb(%E•BV"‘‘E´è•{É‘’B1­E é„qãÈSÖŒ"Éɡ۷)2’ˆÈÞžZ½šˆÈߟúö-¢£nm"((@ƒ ÒjTb‚Rµ3×¥ÜÐÐP™›Ö D"ºs‡Þ½#úlÑÙØŸOþIDLaaµÖ².¬-w pþ´«W‰ˆ6n$€¸FÒ'N¥%mÞ¬Rá”K¯^½¬æ®H5¦«/¯_KµðàÁ¤¡A±±DDíÛ@ÿüCD´aùù}éÙäaa©©ªå¨6¤§ÓŸ—„|ò$Ô·/Qx8µnM..ª•Neܸqƒ»qÿøñ£ªeQï\}iÒ„ôtiªK÷îèÔ ÖÖ ÂªU˜3" „É“!ø²Š4±¶ÜRR°q#ÜÜàÙ3 &mHߣºv•VÄíØÃÓS•rª=z 0@ lذAÕ²( O™º2--ÍÐÐÐÀÀ 55Ui›ÖVrr°cž=ƒŸRSal MMdd@"¾>tu--lÛ†V­Ð§O^ÃòZF|<š4žÞ½Ëk'øæ ΃J%«2²³¡©‰ôt̞ׯ uëBK ©©àó1lºtÁ²eå©£[‹ ïÒ¥‹ŽŽNLLŒ‰‰‰ªÅQeêiiiôõõ•¹é—@v6Ý»'uL¿xAM›JŸ˜ÅÇ@\Õ)€úô¡ ˆˆD"ŠŽ&±XuW*µ¾-÷ýûtäåæ’XLVV¤©I™™$‘±1OD´bíß_tT"C×¶ÊÑÑQÕ‚(Óε.˜,.Ž&M¢™3‰ˆîÜ!€:t "zøjÛ–ˆ(1‘–.¥3gT'k…ÈÞžš5#CCêÒ…6n¤Ü\UËT^²³¥WM//úñGé#âfÍ gψˆÚµ#mmºŸˆèüyú÷_‰T'nMãáÇ|>_CC#–{ŒS½QªvNOO §§§ÌM]¼H—.]»FÍšI«T_¼H€4XøæMÒÒ¢Q£ˆˆââÈÓ“.^TÄ_×®‘—½~MD4hñùtçQ÷îWxÚ42D†üêSÇb„ ¦OŸ®jAJ§ µ³@ X»vmþÃŒŒ ºººù§%&&zxxÔ¸4žZãG´d‰4ÈúèQâñhÜ8"¢€häH"¢3gHG‡¸¿çGhÅ iÂtN»•V”ÐPÚ±ƒ¢£‰ˆ.¤æÍ¥šwð`èäI"¢Ñ£‰Ç£'ˆˆNœ ]»(!Au×Râââ444ÔÔÔ?~¬jYJ¡ c6 _¼xannîííý‰{²^·oßΛ7ÏÜÜ€¦¦fÕIÂ(6m°zµ´üÛØ± Áµï17Çܹ6 ^¿Ff&ÔÕ $îîàj~= mmLž —.aÄìÙ/_âüy¼x¡‚¯£>}ÂÓ§øøáæ†{÷ÀÑzz8|üü`g‡7 9/_âéS5 sç¢ysغB¡´}â?ÂÖ©âûÔjLMM§N*‹=<s†ìì(0ˆhçNê׎!"òò"ssÚº•ˆhñbhÝ:""gç< Ë{z-YB­XADäãCVV´}»Tž5k(,Œ(ß%Qݘ?>U RUž²dÉÎ|ÀÕ¨‰D™ŸËÑÏ™3§ªe`(-0f :v€1cpö¬´¿—»;23áâ¿ü‚?ÿ”Žw耙3Ñ£¢S'XX@z:èëÀË—LJðì._Æë×pçvìÀýûpó&֭í[pã†ü1çI¸u+ïøÞ=ìØÐPxó—/ãñc ‹ÄDàs塞,°¶ÆÐ¡hÖ ú÷‡»»4¹cútܽ {{ptDT”4¼º_?,^,íÀbd„ºu+ûͨ \\\ôõõÏž={ûömUËR,ÊÈF™9sæöíÛ‹ühÅŠn\†ƒQˆøx¼}‹ÆÑ°!bb ˜šâî]Ü¿.]СnÞDHzô@÷îEwë†ï¿Ç­[¸qCz|ïÂÂб#:wÆ‹ˆŽ†©),,  9™éÓ/77·•+WöìÙóÚµkª–¥h”¡[´h! åÆ4h«§§WÕ0 †©©©æææÉÉÉ—/_þá‡T-N(£ÎF£F¦M›VxÜÑÑ‘©fƒ¡ .\ÀÅÅE Fj9PRÂæsýúõãââ˜vf0ªB(¶lÙ2>>þôéÓÇWµ8ò(©F]£F¦OŸž„Î Cµhkk;;;Xºt©D"Qµ8ò(¯FÝëׯ[¶l™Ï‰*FFFÊÙšÁ`0Š$''§uëÖqqq‡7nœÜ§b±XMu…þ”Wß¹iÓ¦2ï³££#SÍ Cåhhh,]º€»»»ˆ«•þ™>øùù©H.@Éõß¼ycaa¡¥¥gll¬´} £8Äbqûöí?~¼cÇŽ3fpƒD4dÈV­Zùøø¨J0¥öFiÒ¤‰½½ýüùó™jf0Õ555wwwË—/—E.lÛ¶íüùó¹¹¹*L©ÚÀÂ… gÏž­äM £ÆŒÓ¡C‡„„.oîáÇNNNä|JFÙÚ¹aÆuY2ƒÁ¨Nðx<®dÝêÕ«GŽÉÑ_–íÌ`0Õ¡C‡vëÖíÇ#GŽŒŽŽæUk;×QáÞ ƒ¡233}||ÒÒÒD"×HvçÎÙ4ÕÚÎL;3Œ/1cÆüüóÏááá%Lû²üÎ ƒQ°°° ™;w.Ç+nó;3 † ÐÔÔÜ´iÓ•+Wš4i °šf¶3ƒÁ`¨Œ>}úDFFŽ;¶pj³ C•=ztß¾}ºººùÇ™íÌ`0ªgÒ¤I7nÜhݺµl„ÙÎ ƒQ-èСCXX˜¬Ü1ÓÎ ƒQ]ÐÕÕýã?Ž?nllÌ< ƒQ½øé§ŸmxžóÜçN‹3¯Ã#"0 £¢ð( }§Á`0Õ>€+Vlß¾5K £ð‚)S¦ôèÑ#44Tßù0 F5ƒÀÆÆÀ•+WZµjõã?J¥R}gÅ`0Õ† ‘H–-[Ö¶mÛk×®é5+ƒÁ¨6ðØÚÚª^züø±‡‡Ç¸qã’’’ô”ƒÁ`TÔZ£ùÑ?ÿüãææ¶k×.}dÅ`0Õ†¢eTI||üøñã‡S¹Y1 FµÀÚÚšÇãWâßÿmÖ¬ÙÖ­[ÙòRƒÁxFFFéééïÞ¶°°¨Y³¦­­íÉ“' 'Ož\‚à2 ƈò666ù2jhh˜——·}ûöqãÆê/7ƒÁ¨ð•ÿËŸ¬‰D?üð€+VH$}¥Å`0ÕNFóg™-Z´xñâÎ;GFF®^½Z‰1 Fõ€“QkkkNNNÞÞÞ<Ï×××ÀÀÀÇÇçéÓ§zMÁ`0ª:z÷LjD"-Z´˜:uªT*5k–^Óc0ŒªNA§~Ê”)üqþÕ«WשSçüùó~~~zÊÁ`0ªœŒºººþôÓOª7,,,Ö¬Y`Μ9zHÁ`0ª¼lF‰¨gÏž—/_^°`Áºuë*3-ƒÁ¨.”$£=zÔ¶m["ºsçNË–-+--ƒÁ¨.ðK¾íææ6}út™L6sæLfÏ`0ïRJk@ff¦‹‹KLLÌž={FU9i1 Fu¡”Ö(ssóÿýïæÍ›Wä¾{ƒÁø)]FŒ3¦gÏžqqq+V¬ÐuB ƒQ½(½S¯äÉ“'­[·&¢àààV­Zé:-ƒÁ¨.”©5  Y³f³gÏfsM ƒQˆ²¶FdffºººFGGïܹsܸq:M‹Á`0ª åQû÷ïÿòË/íììž={V£F Ý¥Å`0Õ…òÉ(€^½z]¸paÖ¬Y7nÔQN †VÈËÃo¿!'µjáøqìÛ }çÄx)·Œ†……µlÙR&“ݾ}»M›6:J‹ÁÐÜ\xzbÄxy!55kÂßýûë;-ÆûHY§˜òqvvž;w®\.gsMŒªÌܹ02‚—XY!$ýúé;'Æ{J¹eÀ²eË6lxíÚµ¿ÿþ[Ûù0øî;ðxEñù07G½zèÑóæ!0°è¯_cûv|ýuÁ77hå0Æèh,Z„?FãÆ°´„¡!jÖD‡ðöÆ›7ZˆÏ¨Ž”»S¯äàÁƒ_|ñ…µµuhh¨Ò9ŸÁЙ™ Á˜7¯àbß¾hÐr9ÒÒŒ¨(îz÷îØ³õë«EؾS¦ 6µkk9·€ôé## WW$&âàA$'€H„þÁ°aZ®‘Q  ŠÒ¯_?Ó§O¯p£"# (ø:~¼à–\NÞÞ·œ)7WíÙõë  ¬,µG´Â¹sÐÚµW¢£ÉÚšËÄÄ„¢¢´S£Q‘N½’7 …Â?þøãÖ­[ÚSu£tø|üø#ò{Aaa8xP­@ûöpù2È娏‰‰ÚLÀãàuݺ-М>¬ÍŠÕ‚ŠË¨££ã¼yó ÅŒ3 …sb0JÅÀ-Z|{ó¦ÚÝîݱjfÍÂèÑX²C‡ÂÎN;õÖ­‹ 8™ÎÇÁ¡àõ«WÚ©ˆQ¨¸Œøî»ï7n¼cÇm%Ä`”#£‚×ryá»K—âåKìÙƒÿýõêdæÌb§³T¿>ý”+߬þú B¡Z™¬àµH¤Ñ›bTG4’Qccãõë×ðööNJJÒRJ F™ˆ‰)xݸ±þò®_/xÝ¡ƒþò`è‰ ÎÔ«âéééïïïåååëë«•œ QQhРàÛãÇáéYðíÇhÝʼ<>„›[EjÉÎFnnéÅŒŒŠÝuò$<=¹Lðä‰Z3™ñ! }ùò¥›››T*½zõj§N´’ƒQ¤Œ*HJÂ¥KX°Ü­o¾Oe§—”„£Gqü8އrjÀÎgÏ‚Xö¢°|ùò•+W¶k×îæÍ›@ó€ F!-’š5±t)¾ùF;KëËÅåËèÑ£ Ñ£ñÝw¨U«²Ó`T´#£¹¹¹nnn¯^½ÚºuëÔ©S5È`’Ñ~ý`o˜?Î]WWjÉÌDvvéÅ„BXY©]IO‡ÒãìÀ  ÖxøÑŽŒ8~üø Aƒ¬¬¬BCCmmmµ“ñ!Sd§^.G‡¸{—»Ø½;.^_ƒ‰Ò™3±yséÅ>ù§O¾Ø¤ ^¿Fj*˜gäŽF3õª 8pàÀ©©©‹/ÖVL£|} tóÊlØPî ±±pp@B‚¦É´iƒš5™†2´×áêêš››{õêÕÎ;k+,ãä„™úÙ³±i÷Z$ÂÝ»åëÚÿþ;~ù¯_k:¢ªP€ˆuçÚk°··_¸p!͘1CþîzhCK¬Z…ºu¹×b1ÆW[_*˜4IS ˆÀ¸qèÓ{÷j‡ñ Màíííìì|ïÞ½­[·j7²æuê”B»¿gD¯^ÑðáÄçS£F$k76£$^½">ŸŽÑwŒ-æ³`Á‚¦M›>zôhË–-:ª¢b¸¸¸L›6­ÐÅ€€€~ýú9::þöÛoÙeÙÔRYYX±-[rvÂ]º 'G󨌲rþ< 0ƒFå Íu£…8wî\ß¾}ÍÍÍŸ={V7}ŠV!¢´´´¼¼¼¬¬¬ÜÜ\±Xœ•••———––&“É222$INNNvv¶T*MOO—ËåiiiYYYgÏž-nIVݺu¿ýöÛ3fˆ*ä)ã·ß°nRR`øp¬\ MÞ%£Üøø`ÞÅÎpuÅøñ Å_¡iSLœ¨öúùsìØ''LžŒ¨(œ<‰úõÑ¿?âãqå lmÑ£23ss8;kø±½ÿ¬^?ÿD§N¨_³g—d€Ï`hHùd4==Ý××7((ÈÎÎ.;;;%%ÅÇǧY³fÅ•vwwo2ò«¼ï•Þ¿‰`Á“»¢gD+++ccc‘HôõîÅ ¿ç‰'þý÷ߪW,,,¼½½çÎ[°99˜8~~Ü·––èÔ §OãÔ)ôï~ýpòd_ú)NÂéÓè׳Æ8sŸ~ʽ>{Ÿ|‚¾}qæ ‚‚0y2zõ–- Áš5èÐsç":gΠIôèÜ\$&ÂÊ ææþä F”£SìØ1//¯ &¶mCf&ÒÓñä üüТ-‚“¸¸`íZî ‹¦M±v-š4)üÚÉ k×ÂÑêÕƒ—glk‹áÃáîB!ÚµãlÞ•sV&&€°0(ÿœ½|‰}û“ƒ¹sqç&O†§'zôÀ… ðôDÿþð÷Ç¥K˜5 â§Ÿ†ýûÑ® @N22`g§ûN£SÆý­[·òùü ä_9{ö¬2B¬ê’hu”;š¦$ÚØðübù›Œ1Ôð Ù¿ýjNCbiM æ’XËËŠfáÂ…ùï}èСaaaÚŠœ•E¾¾ääÄ-`¬]›–/§ÔTm…/‰ÌLzú”^½"" §Ý»éüy"¢›7iÂÚ¸‘ˆèȪW¾þšˆèŸ Q£ˆˆöî%€FŒ z»`sÈ"¢€úôSîÙ¨(ò÷§çÏ+ã½0ÕŽ2ɨ¿¿?ŸÏïÔ©“L&Ë¿˜šš:uêÔíÛ·—ð ··7€UãÇsÒÒ°!¥¤$Éè\­I¡1ÔHER›¼¡1´&…ÎåP¦\Ó7V$ééé–––:wî|õêU]T!—Ó±cÔ¡÷ŽÍÍiölªj»¥ÒÓéÞ=zò„ˆèî]Z¼˜öì!"úçª[—æÍ#"Úº•òò""Ú±ƒš0ˆhß>rt¤Õ«‰ˆž?§Ý»)$D?ï‚Á¨"”.£µjÕpöìÙòF3f €¿ÿøƒ 8]ùè#Õ•èYr Ì¥5)4$–š„-©éÚ“Ôõë×»¸¸>|Xë+í !—ÓÑ£Ôµ+÷¦ML´¼±ˆ‰¡“'9‰ü÷_êÕ‹~ÿˆè§Ÿà¶î¬_OÍ™CD´m9;Ó¯¿=yBÿþK¯_ë)u£r)]FW¯^ ÀÁÁ¡Ñ{ôèàÜ‚jûõFŽ,r_^–¢@RT$µñCË“éD6¥j&©gÏžUmPW÷ïÓØ±dmMii•Y­ÉÉ¡/¸½íÇÓ¨QäçGD4>ôÓODDË–@Ë–íØAýûÓáÃDD¯^ÑÓ§”—§¯Ü PºŒ¶lÙÀÔ©S+ÝÑÑÀÓ; <$ø|hñâ’ÌVP`.ù¤Ò¨8rT—Ô^ÑäD'²)E7]œ¬ï tOf&Ý¿OQQDD;vÐ'Ÿp†“&@[¶ÍšE­[GDtè-_N÷ïë/cCK”"£ù«ÜWöèʉrýPVVýû/dl\ ¤›6•1HŽ‚n‰iK:Š#'IµCQäD‡²(¦R›˜ŒrAÇŽÑ›7DD‹Qƒtæ Ñ!о}DD'’£#>MDtï…†jÙF„ÁÐ)¥¬ŒŒ´··pàÀ/¾ø¢\k’““mll,--ÓRS…H`mäd8xƒ—+¦Œð4Abå"X±Jîö𡽅¨«ÃÍY íàï«W1e 7F‡¸}ðð@ïÞ8ž;2Ä×<;#‘Q•)EoL”뤤¤B·RRRrrrêׯ_ܳQQQêׯ©..àñ ‘ÀÙaaè×§Naôhœ?òœÚdÀC #´0Â4 È€§R‰q[Œ[DȰ7 {³ÀÞí…p¡»õ™¤VI À€ÜëË—ñä ·îµn]4j„Ö­ÀÇaaèØ¶¶1|>þ÷?ØÛC*…‘‘Þ2g0 QŠ[ƒµµuÓ¦M;vLõzLLÌÔ©SKÞx ¥Œ …°·çVŠ÷ì ÁÁ3¹¹4aaKÝœžþY ÷àD,¯‰&°ä#B†³±8]£á…鉨›…0vzHUÅØíÚA¹ƒl×.¼~ å_ç©S1i\]!—ãÄ 8ÀmÁrtD³fˆ€Ë—¹ †¾(½©¶zõêáÇŸ9sfþüù_ýµ@ 8yòäñãÇ·oßnccSƒ­QááØ¼3g";;ãúu89á“Opæ ú÷ǵk¨UK÷¡l¥N2‡x™‡` ‚rqUŒ9üsàŸµpÂÃí…p2ÛªSÅùæîîÞÅ“'°²BJ RR‘Zµ›‹Þ½ #ÆÆØ¶ ­ZÁÝíÂbT.e@õ÷÷÷ðð011177oÛ¶­¸ .ÄË–-°L¹ì%="€èòeÈÒ’ÂéMÈݲ²4ä-9Q¨”ödÒ´j¡6=Õ.’¦%ÐŽ z(!6ŸQ½É¸E©oÞPÇŽÔ¾=Ñ‹î÷äíMGê1GÆ„®Üï‰hÒ¤I|•§á L‰DPl,õîMy{SL w¨§'é~Egxíɤ¹‰Ô1RMRÛDÒÄxÚ’N%T}–Q1Ô £±ciÚ4"¢€¨S'"¢—/iüx:p@¿Ù1Þgtèd«Ö©··‡£#g¼qó&Ö¬‡ß~ƒB“'ae…'0c†î’Qbo€QføÕ7ê#°ÖXcˆ)ê YŽó¹X› ÏX´ˆÄèxlÍ@ˆ ]'ÄÐNNص ÊÃìí±bwŠòŋع“;†àÂôéƒ;õ™'ã=Dw ݼys<(¸´d ´hÑÛöéôéDD—/“PHýü³îò)ð<:”EÞIÔ%J­•êA£âhK:Ý“”õü«'¯_Óï¿s‹R—.-ØÉº};uëÆmÁb04A‡¶Í5jÔHOOONN®Y³&$ÄÇ# “'£[7\¹‚ÐP¸¹ÇÃÓ§pp€Ÿ¾üDعcÇê(¥²/禧nKð\erß„‡¶BnU!ŒØ$F5$". U+´iƒ±c±{76oÆôéøñG\¸€%KЧ¾SdTCt%£™™™&&&Ü q~~1ƒáøqˆDHKƒ‘&LàDs×.øùg,\##œ<‰^½t‘UyIãö[I}‘‡üOʘ‡æFܤ¿»B&©ÕøxܸöíQ¯:uÂÍ›8u Ÿ~Š©SŽÕ«Ñ¶­¾SdTt%£Ïž=suuurr S. ÄÈ‘èß Å­[pwGx8š6E^îÞE«V0g6n„¥%®\á\‹« ‰rÜ’à¶Á<’Hªˆ7£‚uT"&©ÕÄDœ;‡Aƒ`jŠºu‡ÐP8;ãóÏ l¹ŒbÑÑ`Á¹sçôìÙ³ð   ¸ogÎ$€>ÿœûV.çöZ׫WåL:U(‹ej›ò¯žÄÆrܧ¥‘QF)Ô§ÍŸOÙÙúÎQõÐÕL½rš¾^þAbDˆÇ£GÜÖÏë×¹ëË–ÁÜÿýÇ]áó±{7ºtAt4ú÷GzºŽÒÓkzÃÛ 'ê ¤öØašZA„H±5“Ð:ž±ø!þ9HgSþÕ‡Úµñùç`i‰G°gÌÍñø1ÎÞ=06Fv6>ýë×ë;QF•AWÎÕV;)iÐ2îÞTdÔÖ3gbÍx{ãòe06ƱcèÚ!!2§NUñíÓf|xˆà!€lîI¹±ÔûR„H"Å_™M ¹ŽWj°Ó« M›¢iSprÂùóHJ‡K—pæ 220o""ðûï8ݺé;W†þЕŒ*7Ô´Fy<´iƒ¼<Ô«KKDD *ŠpZ¸¾¾¸rÜÎ>kkœ<‰.]pá¦MÃŽ:JR똪J*áÞÛ±Ô›<ÏÃó<ìÍpx+©E¨É$µ: âã¹×;cß>ÎàØ1üü3¢¢Ð­=ÂýûèÓvvzÌ”¡t4X <íýˆr©}û ¶`Oy0Eûöj6“·o“©)´|¹Ž’¬4²Ë`™Í<á«!ÁÁ4owBŒÒÿ_éHBÏžé75Få¡+mÓ¦ €Û·o\Š¥(5•–/'€¾ù¦àVVÕ®Mýû¯Z”'¸CœvìÐQž•O®Š¤:¿#©siO&E1I­†ìÚE}úÐõëDoM©wî$"Š‹c.Ôï9ºZðT«V­ÄÄĘ˜˜:uêp—”Ëwí‚>ù:ŒœÿSÓ¦xô*C Û¶ÁË ††8v Ÿ~ª‹TõˆªeêM ²Tf¢ò-S»‰Ð€Y¦V7¾ú ‡áñcÔ«‡öíӧѼ¹¾ÓbèȨX,611144ÌÍÍåóßþ­Z…ýû±d <=Q³&¤§#ß±4/..xõ ;wbÜ8µp‹cíZ˜›ãòe´i£õl«ª’z[‚ IUõ÷s6Ô_ŠŒò “ÁÀpqAf&ad„–-Ñ­Ö¯Ç[?tÆû€NdôÕ«W 6|óæMÑ%Z´À£G B×®wíÂøñhØ¡¡ ®aÂìÚ…:upí5ÒzÂU 9ðDŠÛ‹qUŒ´w$µ½îB¸1ËÔj€B/àìŒ;wо=ðâÒÓ±`FBúίz’””diiihX%š:™'.¼hTIVž=Ãë×Ð¥ µN=€Ñ£Ñ¼9Âñm›ÚuÛ·£OÄÆ¢¤¤è"ç*…œõ[Üm€su±ÆL`Åç\¨W¤À3í£0=f"DeW£ªÁçÃÙÚµCh(÷¯ûøqlÛ†+ * çÎA.×g’ÕŽcÇŽ;VGc’åE‡2Zø˜¦K—àꊙ3^„¯D À?ÀêÕPîÄÏÇЇ¡U+<}ŠÏ?ÇÛóJ?€³!F™a‹-î7àüý˜ÀZ€$Im…I Ì߯ªãìÌ£Ó±#–-ã~víBß¾œOdNŽ>Ó«FÜ»wïÀ«V­Òw"€Žd´à&Uê×Góæ\—\)£W¯~rð`tꄸ8lÜXø–…üýÑ 1n¨V(-S·Øânñ–©no-SoK «­…qrŠ:jÖD³føì3˜7ŽŽ8wN¿ÙU‚ƒƒ,_¾üÏ?ÿÔw.ºY7:gÎëׯ/¶„BA66ЫW…o)ËkÔ ää"|ôˆjÔ €æÏ×fÆÕŸb-SÙeju¢m[($„ˆhÞ<úåJMÕwNU©Tšž¦¿rá®þЉŒ:ÀwÏmxú”._æ^{z@{öñ|¯^ë˜ßåâEÎã9ßß„¡NœŒNd“wy¨KªK8Š#ŸT Ì% “Ô*‰BA·n%&’¡!RBÑ¿ÿRf¦~S«B(›¢ùê1ÈhÇŽ¾afF¥¥­^MÍœYÄó·nG¦¦{÷G|>:¤ÕÄßCò%µW´š¤6 §!±´&…sIÌ$µê!•Òñã´nQHT¿>Éd¤Püƒ7ûã? õª­­­Ÿ>}ª¯|*qŠ €»;<<› ¼½v­ˆçÝÝñÙgÈÎÆêÕEWðå—X¹ ÆŒ)b€•¡‚L°Æu\[l1Ñ-Œ &K°5£ãÑ,ž±X›Š€\µ- =bhOO,X¹¹èÞýûC À¹shÒ[·ê;?½rçÎBW’““ûôé£TžÊGûëFe2™H$""±X\Òª®ìlÔ¨©©03+|÷ñc´j>Ïž¡I“¢#Ìœ‰Í›am«W9F™I’ã¾Áb‰Õ\¨ W#xˆÐ^„ŽB˜3ç”*ƒ\³gcÓ&,_Ž~À©SˆŽÆˆ07×wr•K»víî*½âÔqww¿xñ¢©©ie'¤õömdd$€Úµkq/>ž®_/èª+‡Ó/^,:ÐØ±иqÅÖ$“ÑgŸ@S\œ¦yÀçBÝø ˆ¡åÉt"›Ò>øŽdA¡  (*Šˆè£ å扉úÍ«òÈÍÍ-¡}Ö¿ÿ¼¼Êö¤Ð¾Œ^¿~@ûö틸7e ´u+÷íŒÐêÕEzýš„BèÑ£b+ËΦN8w(6¯ ²ä˜KkRhH,5 W“Ô^ÑäD'²)…IjÕ`÷nêÛ—3çwq¡V­èÍ}ç¤{nÞ¼YrÓpòäÉ•œ’öûlE/UâìŒví`iÉ}[ä"ü|5ÂW_A.Ç÷ß[™‰ Žƒ£#‚ƒ1bd2Írgp–©ÞV8\`æZÂC>óKžˆÖ‘èÅÉðÏA KÕ£Gã̘›#"IIHJB½zJ1mõœÎP¦777мyóŸþù‹/¾hܸ1€;v¬Pî«4´.Ì6l0³È)øB¼zEY[ë#ÃYŽ*ÝÇŠãùs²µ%€¦L©HÆŒ2­ À\òI¥QqäÈ,S«b1×móó#€Zµ""Ê̤¤$ýæ¥}&L˜ Ô®&MšÜ¿_(¤)×ÿ%&&ž:ujÕªUÏŸ?¯´”´/£ Áš IDAT ,°fÍš"Òõëtÿ~Á•:u ÐÐbÃy{@½{—RëÍ›dbBýôS…²f”ƒœ]¨™eª~yó†–,¡þ!"Ú°Œß·ÖnnnÜÝÝãâ∨gÏžþûï?=¦¤ýN}Ѿ$JîÝCçΘ;·àJ§N@1Ëž”,Z„š5€óçKªµCìÛK—bçÎ %Î(+Æ<¸ 1Í{ìðÄ'êÀÛ "ˆxˆáßl,NF—h¸Gaz"öf!‚µT" bõjŒÏŸC"Aưmvî„D¢ßì4%;;ûéÓ§žžž/^´³³ЧOçô»VëÂÜ­[7.\(â^X¹»«u½×­#€¼¼JЍ\¨ïî^º‡ø¯¿@††tölùghJÑC mI§‰ñÔ’¦%ОL •ê;ËŒðp’ÉH"áΗPnö©¾L¯\¹2þ|…Šܺu €³³³³ÒþºQ‡W¯^………999•^úêUxx E <|Xl™ìl8:".GŽpGß–À·ßâ×_aa+WЪUùRghUËÔ ±ÚÓ¶t`–©•‹TŠýûqù2vì@z:ìíÑ£üüÔ|}« µjÕR½"—ËkÕª•’’òúõëFz2#Ö²Œ‘±±±D"ÉÉÉ1VžXˆ{÷œŒž=!€X KKÈdHI)˜Á—M›0{6š7ǃ܃šP`Ä:„ºuqý:ìí5{C - ^æ!X‚ ÜÂ.Ô6´2‚»"47ÒáC€ „.]€èhøûc̘êíÆ?|øðC‡mß¾}òäÉúÉ@»Ûøøx5kÖ,¶„j›å;v$€Îœ))®DBMš@»v•žDn.yx@Í›WãÞË{Šœ(TJ{2iZµVïø·‰¤‰ñ´%Jˆ­LÕ) ôä ÑÒ¥Є úNH3|}}Œ1B_ hùϱ»éóéÞ={ªù.é„_##nõè²eJKIB$ÂÑ£pqÁãÇ<¸Úª¿_ðU\¨ï5`–©úÁÖ®®ÐªZ·†² 7kFŽDX˜~S«}ûö Ð— ±vUùرcú÷ï_Žg”ëÜ>ù¤”b25kFmÞ\¦°¯_sƒê#G²óm«ù–©‹²LUúû1ËT‘“CÄãq­Ô‡«Ù/ƒƒ€;wîè¥vZ£âwó(iµ“’ðpœ>ÍȤDyªÝ¥Úç1²jU™NZhÔþþ03Ãþý%íƒbTì 0Ôk¬q­ëÁÇ£ÌÐÀÙ„ 16¤ctµ@#F@ÿ÷¥WyölIGŒÉöí@@GŽ”õFU%^F'²iy2 ˆ¡†*ÿ&oh@ ­I¡s9”Éæ§4F&ãfg¿úŠš=[ß •Fjjª@ ‰D999•_»¦c£ýû÷  W¬X!‘HzõêàôéÓD¾bÅ ''§ºuëæïx-š  ‰ËTåÇ@K—–#Ëï¿'€ŒKٛϨV$–(©J¿t&©šqþ}ø|nÄàˆj30=®\¡+WԢܼI5mZ¦*K=bä] š0²±¡°°²>Ũ>”Å25•IªÄÅ‘‘ …œÕiD„¾z‡¥K—X°`AåW­©ŒæææÖPšØðaÃÔ¸~êÐAí¢TJ&&Äã•Õ{vÐ hÖ¬r$*•Ò'Ÿ@_ŽÕ f™ª#ÂÂhçN"¢H  1cô:/^кuëʯZ ž¾þúëâ4ÔÊÊ*¶P›1"‚ºv¥iÓ GéÖ:q¢LU†„ŸOFF\g£ŒddPëÖœˆgg—ãAFµ%KQ ©ÅøûÅÈôeuãï¿ÉؘæÌ!" ¦Ó§õI$333_éí$-Èèµâý™vìØQÖ( –oÄs̘Šl¿ˆŽ¦†  IÆ~{>,˜eª‰‹ãN~0€Ú´Iß Q¿~ýì+4ƒ­{´³üÞU¹%B]úöm:z”Äbµ‹GŽ@\Ö*_¿&##èñãòåúø1YY@S§–ïAÆ{DY,S#™¤–†BA«VQ£FÜhÜìÙzöVóññ0iÒ¤J®W;2ºfÍšBjnn^téÆ  /Ô.ÆÇ@¦¦Tö㨦M#€†-wº—/“PH­__îgï¹*’ê¬.©Ì߯,(ûu—/skÓÓõ–ÉÇÔ¯_¿’ëÕŽŒFGG Ô—~ûí·bKOŸNƒ–Q"rp €îÞ-k­11ÜÄÔåÎxÿ~âó‰Çã\ "*³ejµÚ'YIdgÓ¯¿r[µÏ£J±Ò …¢N:ž={V™õjmO½rŨ’öíÛË*0ò¨î,ã–y%ÊÕ>}Ê]­]KÑùóyœñ¾£”Ô4-ÜÔ%µ]$MK ôPÂ$µ$€~ù…¨Ò-¢ÇŒ`SåÖjMF÷ìÙ£ÔP‘HôôéÓ’Š>{FGÒ»NmÞL@ù–Q¤¦r“ÂY³ KKzø°"3>d*’Ú’ùû•FVmÜHÙÙ¤PPûöÔ£7§uvîÜ `РA•TiQF³²²ÌÌÌ,-u¶}ÉhÕªÂ×ïÝ#€š4)_Å?þÈ­aª€#\NC†@•c1?ãÃF¦b™ÚJ]R›EШ8&©„†’¥%Õ©ÃIjÉí+­ÍãñÌÍÍ¥ÒÊÏÖ¦QÞ„ \\\rssK)wð À-äUE&#só¦Υ’•ÅYA=Z¾t•ääP—.PÛ¶”™Y‘Œ›ð<Ú“Is©cdþ~[Òé–øƒö÷KJ¢«W‰ˆ&>Ÿ¾ùFç56oÞÀUe­•‚6m›'Nœ¸mÛ6‘HTJ¹aÃpâÆ+|] €»;ܸQŽZMM±d ,]ZŠÕ^‘ãèQ8;ãî] ;Ä’Q>ì 0Ê ¿ÚàF}5j¥¿ßÚT ‹û ýý¬­9gö°0pp€;w««•¦y•éö¤ý#íJ'- 7n@(DÏž…o}ÿ=V­ÂÂ…øßÿÊP*…‹ ^¿ÆîÝ=º")½z….]É“±}{E"0ʆŒðg&r Ö|äâw˜½§0Eȸý®ˆ¥ò×Ù˜‡æFpÂÃîB?¤#ý^¾DƒàóѼ9¢¢pþdôáC´j77„„¾uò$ €‡Ëó¯¿0i5Bh(ŒŒ*’ÕíÛèÙÙÙX±Ë–U$£4Ä„‰ hŠQfHW e$þ®…žE|XFâäø+¤ˆ”!M±¦|42@Ƙ£¾öR׌x9w¢ßm ž«x!‹xp{+©í…}’ššŠ™3qÿ><€mÛ0i’6Ï(ÍÎζ¶¶–ËåIII–%”©=ô!£II˜0M›býú·RSac##¤§—O år´l‰'O°e ç=[NœÀàÁ˱c&N¬`Fñ,NFŒ;ßžšgCXct< yèc GC¤(àŸTyØ`ƒþUïÀË9n¿•ÔyÈÿõ3\à!B{: aþž6Òó‹!áÿþ_Þ½¡Ý.øG}tåÊ•£G4H›q‹£ÒFaËŠ‹ tóf¹‡²Y ÐÛÞV8QÁ*’JÀó<ìÍ*,©)òùàñ@„)SУzô@n.æÏG||Åcº»»[YY…††FFFj/ÓbÑÇØ(€yó€ï¿‡³sá[ÃÍ  "¢"‘?þ/â»ï¸cD+†TŠ€fÍ+«Š‡ú¸œ‹?3qSŒ\õJàUÂooŠñE<7§$veb  lÔœð} ve–^ãGÆØU«Ø»›Ó±îílÓ,à]ÍzÙ Ü“rc©÷¥©|ÈöÜXjg!êV™ù4ÍY»‹ã£péRŃ 2äÈ‘#þùçDÝÏsèIFK€ÖÖHMEd$ê×/÷ã·n¡S'˜˜àåKØÙU<Œ t놇ѽ;ÎžÕæ<â{Ç¥\K°7 Éo»ôÃÍP[>ð­úÁ›Òá—…6BÔ`¢j ‡ÒŠŒNN@ÀÛv±¯->­z³L&›pO‚ÛbKpS‚’’Êú¬““SãÆ“’’”&¤:EO2ÚªFóæEßÕPFÝÜ0r$¤R†GóCýû/ŒŒ°n6nÔ4Cg„I±0gs jð1ÁgëÀµBû0ª#Æ<¸ 1Í{ìðÄ'êÀÛ ½ŒaÆG‚þ9XœŒ>1œ¤þ™‰)ªØX^Ñ`Æ ìÞ «Vaýúò­çVºwVÂ|}Õ™ ++ðùHO‡q…ö¸¼~ Èå AQœ”½{1f x<<ˆ!C4öž¢•N}¶9eéÔó`©ÞÈTÀ-6Û¢Ÿ Þtý@‘O¥ã¶·%ÈP™Ü· £íEpÂÍH£M•ãG˜7ëÖ¡U+üó\\8Žðóó1bDŸ>}Ξ=«ÓÜô$£©©8}Ba±ªÔª>D` <<*XÅÔ©ðõŰa8x°Âi°r%–/‡±1¸•­ u4”Ñ9†Æ¡“~E-&.D‘SLш”!¤,Ø vQÈ'Rn›é*’j-@k#¸‹à!Bs#}uQËÊ«WpsƒD‚§O‹Xé£Jrrr­ZµŒŒŒRRRŒ+Ö +zúÄRS1jæÏ/¶€†ýzË—ÃćãÖ­ŠÉgÙ2LŸŽÜ\ „ÐP-d¨s*rh´©¼¹j𙆋ha„IæØb‹{ p®.ÖXc€ ¬øH–ã|.Ö¦Â3n‘­¸-Q[\Uu¨SóæaìX8;#.>>J‹.immݺuk±X\ÂéÅÚ¡r6K&+‹¾ø‚æÎ-¶Àß@ƒkTË‚Ð'Ÿh$™Œ>ûŒ3–Ž‹ÓNÌ÷ˆÞÑ{‹Ü Z2«ShCšF ȉªöÎϪ‹Ò2uZµŽ¨f–©ãÇ@S¦[`Ñ¢E-Z¤Ó4ªäØ(€çÏáìŒZµ4ÚÊœ ¤§ãÂ…"Lù*@N>þ7o¢}{\ºSÓÒù`аS¿  j VE5cdø_âåøÒ Ÿ±‹Dȸ±ÔĨøû™ðÐVÈ­£ê „QÕL=yK–àðaÎÆô]Ο?ß»wï¶mÛÞ¹sGwièOFOŸFT†G‘NVD°³Cb"^¾D“&¯åDZl:tÀàiã'Ÿ˜ˆ.]ðâ ÀÿÁ :¯ÊÓ*ýbñämßê€:cÞ]œßh°í5Øâà‹)ð€#àb"ß2õ²ÑÕÓ2U,[[[‹Å⸸8[[[Õ¢¿‘¤åË1e ž=+ú.Ǻj2< à›o`g‡[·àï¯Qœ|lmqü8jÖ„¿?fÌÐNÌ÷{•?(—Þn"*´í[L›3>æXb ).æâ¶„»¥‰†f§¡¸*®x(†*öjŠ5Ö¸V·êc‹-F™¡r ÁlÍÀèx4‹€g,Ö¦" YUo›¿H$òððP(´byò‰‰‰mÛ¶ÕŸŒ„‰afVlÍg™˜™ÁÛ–,©È#Eââ‚ÿþã¼ËåÒÿ^3Ѽ`ÑÌÖ tFÛ(TŸv_‘#F™€%g뢇6¦OMyjÛ]>˜å¢•‰L°ÆA*’êd"ÅÖ LN@«ÈIͬ2’ªÓ3EV­ZuïÞ½ª:6 àòeôè6mp÷®Fq$8;#"{ö`Ô(-%<ˆ‘#A„¿ÿ.â\©’€\lIÇ)€½:‹0Í¢À2#R†îÑøÃŸè`“û] &#AŽ/Ͱ¸š{‘T/å¸õvOê#•Uý ™7–ê!*¼Î·2¹ÿ~›6mìííÃu`ØÖ©S§›7oêOF?FPÜÜŠÝ+›“ƒ5 P -­¤FkYر_}GGŒ…pΩ¡ˆÐ¾=îÞÅÏ?—´{ªˆÅèÓ‡  D¥?ò¡Rªß(ã½Gi™ªt¡~ ­$ËÔ¨¨¨ XZZ&%%”y‘bzzº¯¯oPP]vvvJJŠO³fÍò „„„lÚ´éÿþïÿô'£™™8r2&M*¶Ì›7hÜÖÖHLÔªÏӧѯ¬­ñòeÑ‹U+Lr2<<ðìzô༠Fi”`™ZKÀ¥zˆÔÖÒ•…?3álõ•Ë...¡¡¡×®]ë¬\TÇŽóòòš0aŠ+„B¡òÐf›ððpà¿ÿ:Ý#U11])ÅêÕ#€ž=ÓN¥={@Ë–i'š*¯^QíÚЗ_’¢Jî›c0ª09 º%¦-é4*ŽœÂÕö¤¶¤i ´'“B¥¥Ç¹%¦Fo¨I8íËT»>sæL+V¬(K2[·nåóù ,È¿’ïûnyýɨTJ£G“J¢E3t(ôçŸÚ©4(ˆ23Óɦøà`23#€¾ûNûÁŒ†<=”p’ê¬.©í"iZíÈ ‡*²µ¢ Ú’NÞýòN¢¼·×ÿûï?¥ÖîïïÏçó;uê$“˜4¤¦¦N:uûöíE>RµÇF¬_ùó1e þïÿ´ÐÓþþ˜;¿þª€ªœ<‰Ï>ƒL†ßg{œ ÍQµL½%Q[Õo#@«büýüsðmÄ„îÆØbs>233­­­‰(99Ù¢¸ê233Ξ=«<¥¹,èUFOŸFXFŽD­âÏ'»v ]»ÂÍ !!Ú©4$­[ÃÐaa°·×NLU¶oÇ”)pøpEâb0ÅP.ËÔ{|•ˆ$9\ ñg-Ô3@×®]¯]»vüøqOOÏâªøé§Ÿ–.]êààðâÅ‹²'¦WwƵk1g?.©L»v ñø±FGϫҢFŒ€DÂj¯u¾ú K—B.ǨQ¸qC'U0$ÅY¦Ö(Ê2õ†«­ÑÌÏòðyH¡l]–¼ìéÀÊÞU¢×ÖèÖ­xþ“'{(“’.]pý:ΜAß¾Ú©÷ùs4o…B;GŒ¼ &NÄΰµÅµkptÔ~ ã-2Â)nˆ¹m©Ù*’VS A¦&=›ÛÎÕÕÕõÉ“'EÆ‘H$"‘Àï¿ÿ>£<ƒrzmN›ŸR4o=J´è_í䄉!—ㇴSÛ¶¡o_$&¢_?$&꤃0à¡3,±³žØ#°ÖXcˆ)ê"G‚|ä~³v±ýzþÓ§O#‹Ù)“ |Q^K=½Êèýûظ—.•RL+VO…P1r𠦾'ÅahˆC‡Ðº5^¼€§§–·N1Œâ± ‘š¢©çf«<ËO/\c6bòùóç‹|ÐÄ„sÍIzçç”””¨¨¨âjÔ«ŒÞ¼‰9s°o_)Å”[BoÜ€\{›ëÖÅ´i ÂÒ¥Z‹YssøûÃÞ·naüx­Ùô1Œ¢ÍÃ÷)è‹–ø2¿¤áR.²°ä‘kZ¬Óå£ÆßŒŠjQ#ëÀŽs[·ÁÚÚºiÓ¦Ž;¦z=&&fêÔ©Êþ~‘èulôÎüõ:wÆèÑ¥”lÔáá ››ÖjONF“&ÈÈÀÅ‹èÑCka ñä <<šŠo¾®ja0>xnˆ1" yhiH6ɱÒ;W_þw øäqñÛCï€0cb„uê¼äðáÃÇ'¢yóæ}ýõ×àäÉ“Çß¾}{ƒ Š­»‹bõÈÈ‘¯¯–ÃþðÔµ«–ÃâÒ%  _ÕmE ÆLbvÎô»¯Ænù«ÍG=U7Î ÞÀZ ˜ÇKx€!Ÿ/—Ë‹‹ãïïïááabbbnnÞ¶m[±¸”3õÚÍÊŸB"Á‚¥”ܸsæ`Âüõ—–pp@BNœÀ€ÚŒ\ˆýû1jx<8€aÃtXƒñ!!‘HQF<^w¢®€ÐÅÚÚäÓOqêRR^N@#{û×ZµpÖ«Œ¦§£F ˜™!3³”’ÁÁpwGӦŞÝTa~ýß~‹-pÿ>øº)^³K–@$¹sððÐaE Æ{T*½råJ@@@PPн{÷rÞÎß LM=23{uLMM1d>ú~~¸rb1ÌÍ/gfö<<<µ™“vÛÕåfÖ,Z¹’Šo`sH¥dbB<%&j9Ü\jЀڷOË‘ßeæL¨fMzúTçu1ïR©400píÚµ½{÷6U9ØœÏç·kÔh‘ƒÃ9#£L€20 OOÚ¹“óÍØ±ƒ”×;v$`·™€‘#Gj7=}ËhÙéÞ:~\û‘·m#€œœHZMÉhð`¨Q#*Ê'†Á`ä#—˃ƒƒ•Òi¦rŒÇk×¶í¢¡Cõì™hiÉ©$G]»’¯/%%‘BAK—’ íÛG¦¦PÿþÔ®k?ùÀ¼y󴛪¾Y?rbÂ4lXJÉ.]på ®_Gñûa+ÈĉðñÁÓ§øë/xyi9¸*öìA¯^Ü»¸tIÓ3¦Œªñ4wˆèîݻʱΛ7ofª ÷µk×®k×®66EFÖ:y²`Å·³3&MÂÈ‘hØ2ÄbðxxþÉÉ?R)ÆÃСøì3Ôªݸ1€zõêižjá¼õI¿~emc=Jõì©“4öï'€êÖ¥ìlÄW%1‘œ  ~ý(/¯ôò FF.—ÏŸ?¿Ô¹ìP(ÁÁÁ6l>|x-u—¢Æ{yyùùùÅ^»FË—“«+×ö¨NZ´ˆ=*DÎÎ4mÑæÍdhHMžLyyÔ¦ ôË/ƒàçç§ñûVCß2º};-]J—^21‘x<25Õ‰ô(Ô¶­òƒÖ~ðwyñ‚jÕâ~Æ FµE"‘Œ5ÊÝݽϾ|ùÒ××wøðáµk×V•Ά *¥3::šââhÃeœû²° // T›Pyò„ˆ(4” ©ukÚ±>4"2 IDATƒhî\R(èða¨^=ÊÍíС€k×®iéàзŒ– GGèÎ÷÷'€¬­)=]'ñ që7jóã•Qƒ¡m’““?úè#3gÎ,ã#oÞ¼QJgõ¥ï 4ðòòÚ¹sçË—/‰ˆ22hçNêÝ›SC€LLhìX:vŒrsÕ"ÊdÔ§pӶׯÓöíÜSßOD$—SóæЦMDT·n]ZüHÿ2BëÖÑÑ£e*Ÿ/ò´Ý£Õ·ŒîÜI]¦Â[·–£p 䎉×U…øãÈÐΜ©¤ ¹páB •p_¼xQ¨@bb¢ŸŸŸ——W!é¬Y³faé$"…‚Σ±cÉʪ óÞµ+mØ@QQEg°w/Ò°aDD ”œLD´r%7e¿nW,/œœò7@FDD¨[·®–?ýËèƒ4w.•qÄ÷þ}¨qcæÓ¿?ôí·:¬¢óç@æætï^åUÊ`T”}ûö Uξµ¶¶V(D”œœ\¤tÖ¨QC)=R=݈ˆèΚ=›[¸­ürt¤å˹±ÎwÉÈ ˆˆ¢¢ÈÜœ¾úŠò.ZDñù´ukAù¿þ"€”k¯]» C‡ZÿLô-£åB.' (&FWU‰D¤íÑ“bQ(hìXnÀ›7•T)ƒQ~ärùìÙ³ -õiÛ¶­——W³fÍø*›-,,<==×®]\X:‰èåKZ¾œš5+PO;;š=›‚ƒKª^"¡† ‰Ç£›7‰ˆRR n-XÀ-¼ß½»py€þþ[yÁÏÏÀàÁƒµña¨¡oÍΦŸ~¢•+ËZ¾woèßu˜ÒˆД):¬¢ õêE5k¦öƒÁ¨2H¥ÒI“&»p000èØ±£··÷™3g²²²Š‘@6P×®ÄçsêinNcÇÒ¹sô®Ôæ£PÐîÝÜÄòÒ¥Ô»7=|XpW.§©S¹‘±ýûÕôõ%€\]óƒûøø˜5k–ÆFaô-£R)ñxd`Pú~P%ßO@éÇ2kBX@P©[6ÓÒ¨eK¨{wÒ` ƒ¡ RSS{õêàÝ5ö†††S¦L9qâDFFFÑgfžv72¢á˘v/’õë  Þ½‰¨°Úæåј1HTxí¹Xüî&ïyóæX›?û¤=ô-£Dôý÷´f I$e*|òdeXÛ}õ4b„nk)DTÕ¯ÏÕ[Æ?* †î oÖ¬Y íPWW×”w{QR);FÇ“±qÁ~ÍÞ½içÎ2u¹îÜ¡¥K‰ˆ’“©E Ú¶êçÒK¥\ÇÑØ˜N*üøÆP«Vª¿J#Gް[µã¯%ª€Œ–‹ÔTn첌²[1¢£Éؘx<º{W‡µ¼ËǤÜ#¼hQ¥ÖË`ƒ\._ºti‹-A JÚ£Gn#“BAÜ"¤ü¡Ï¶miÆrÌ7dg“µ5Å®`ÉÍ%OOn5þ•+E<^»6tø°êe—.]*ßGPª€ŒîÛGK—Òóçe-¯™¾qC—9}û-çhPÉœ?OFFÐÆ•]5ƒQ<.\X½zõÀ mÙT2zà@Å¢EܬŽò«IZ¾\m¿fÉDEÑ”)@D´y3}ÿ=¥¥Q,'‡>ý”3K»}»ˆ¿üB¹»jÀ6jÔÀó²KM™©2:lÜ:†²0y2äã£Ëœˆ¹U/ê¶¢wQZ{ñùºIc04àÅ‹»wïž9sfû- ßÎѯPª§­-Ížýÿìg\WÆŸei**bÊŠQc‰ÝX‚ÝØ¢Q‰ÝÄ{byUl‰k,±L4*jìb5ö†½`A°!¨i»ìž÷ÃLP©[föÎ.óÿí]fî}D8{çÞsΓ¹^S-â;ÚåBBßì­xñìÈÅ…:tè÷µZ­­­­B¡HÑeCVO$F÷ì¡E‹rÌËÊÆPÏžbj"""__SìÃæ2µ½=;Ç`v™<‰‰É8vOοØÚv-[öä⏻gE¥¢Õ«éË/I«¥äd8ð£ƒøL¼~MõêñÙ9EŒŸ~"€6ÌôvTT=´éŒ¨¾Ü»ÇÅ&1‘o räˆèseeð`ÈÅ…<`0»ŒL¶$%Ñ–-Ô©o/ÆeuêDþþ”œ¬ßP iµ””DeÊä¶ šAL ߨ©bE¾ 4+oÞ³3˜é+ÁÁÁjÕª¥ŸHÝ@½qƒ¦M£-[t½^«åw¯M!Ïm²Ô¬Éàè\¥â7€*UâûxËȰB­¦¨_?ÊÚ&™+ÄÔ—  ªY“/_Ü¿ŸÎãúˆ¾K^åÊôôiŽ—qq-Zdýʾ}ûtìØÑµy!0º{7¤Wi×¥4S¶­dXŒ˜`®¬$$ð¿õëS¶ùÌ22bsæ C¥K¿?8òð  ¯¸ã¶&ׯ'€>ÿ\§[ž=ã[ôÖ¨‘›mDt499@gÎdýâªU« 6Ì Ñy ¦‰›ŽÔª…Ù³1h·4j.ˆ¤è=vv˜>fÌÀ¦ƒ¦£`A>Œ på z÷†Fcj2ù–G0kªWG³fX±/_¢T)LžŒ;wpÿ>&OÎÛ®"+oߢ_?Ô­‹ôt „•+qøpÞw…†¢Y3<|ˆZµpü8>nNúK—âÝ;x{gk1úÞsˆ›E'(ˆ¡Å@6¤§SµjІ ¦˜.+÷îñ›â|Êȼ'2’,ø¨ÚÝÅÅÀc÷‰Š"µšÔjòð =²oßæ3@6̦W^¦)I¡È>Ѝÿþ6oÞ¬§t@MK£Ù³iüx=nIH ¥’llLáùADÛ·ó‡Zún¢ ÅéÓ|ÆŒ`22’@ëÖQ“&Ù´I6¾4yÕ*rt¤ß~#" ¦ˆ]o¼qƒ?ãmÙ’ó¸xüx(ç­ÏV­ZøGœŽ”£Z-Ÿp®W>W­ZdSÀ Z-¿G)v²j.øû“•)ôÇÌ4ÈXYÛ$g¸g›÷®j5=|HDäïOo‘¤;.ðgîÞÞy¯–ž?';;R(r±Æ¨Zµ*€»ºøéÂ(ýü3­X¡ßZoÄháBÑ4}Ì¡CüŽi,F²…KN¶µåË
±à@]oçú±õé“Ë%·nÝP½zu½õè†4Â(çU§¯³[‰Páòá'N4ÝŒYIN¦&MøºÜÏ.eò9¯^ev'.Xw'6 Àå£G´w/Q` 9;dã¡»vñÇ$ߟ¹-^N„†’ Y[óû°9päÈÞÞÞ Ë i„ÑcÇè×_éömýîêÒ…ÊÕ•P`Lo1’-±±äáÁŸ`ŠÚ0PÆ1²M²¾LÖÖÐêÕ¬¥È˜œk×hÌ*Wî}ôtwׯM²¾hµ´c-YBDté5h@çÏ;æ¬YüÂYߟá7H¡ tÙak×®€ƒ™üš„CaôÅ Z´ˆöíÓûÆúõ  ãÇEД3/^°±É®ÅƒRIû÷³–"cÂÂ2»»ºæíN,ׯ“BAöö‚¥—f˜Ë¯_¯÷½]»@£Gërm5\¿~]ïYtCaÔ`¸‹yóL=ï¸q¹Wž™”©Sùê=±UdòA›d>z:9åíN,×®Q×®|èüþ{Z¿žÔjcÇÔjiäH¾n꯿ô¾ýÒ%þgþåK]./R¤€˜˜½'Ò i„Q­–Ƨo¾Ñû´„«v7}8˰ÁKo´Z0€OÌk¯]ÆÌx÷N°6Éëê¶îÓ †¾ûŽ*PÀÀ§¨tO=LLL`gg§í0Va”ˆ¯ŸÕ·ìÓ§PÑ¢ N«gÎ$€š65õ¼Ù¢R‘·7T½ºmte$…àm’õ%2’† ãÓ`BCiútªì9ÔjêÛ—²·Ï»[s¶œ>ÍçÀ궺¼ÿ>wwwCæÒ É„Ñõëé? iNÌU¶™þÜ<.Ž÷€Íê‘Í„øx¾]K³f¢¤ʘ€ŒcwîG‹{Õ®MË—çÖò]X¸-‚‡ÉƆlmv^P©¨gO>ü$׺54mšŽ—?~Àç:¶ˆ6É„Qƒá/Äi#˜¿üB`d1’-ü¹mÏžR‘$£#P&wâŠÅ=vÏ–õë©\9¾"hÍ[7$'óã… eÛ ^'Nœ €ŠÑ=ÏË–-||| œQ$Ðýžã¯¿0hΟ×ûF“uÂÏÊ÷ßÃÍ ·naϳg¥ti9ggìÚ…~`­FF"#±p!<=áá… ñô)\\0f ΜAh(fÍ‚§§)dhµˆ€«Wñìþü†GÍš‚Mñî:tÀ‘#(V 'NdÛ ^'fÌ€±cáì¬ã/^¼€x}ï9Ä‹Ðú1|8´j•Þ7^¸@yzŠ IÖ®%€ªVàìR(Nžä#–-c-E&âãù6ÉÇ‚µIÖ—7¨V-êÕ‹ˆ(22“½»0ÄÇSÓ¦P©RdLÇÏþ!€ŠÓ«_åÈ‘#üú믆ϛ’ £ÿþKëֲřšÊwl£â-OT*ª\™Ú´‰Áì9±};)deE»w³–"ó¢¶I6®Ì)"‚¨T)±:ÝÄÆòíQÜÜ é›—VË›ÔÏŸ¯×}_~ù%€={ö>u^H&ŒCãÆÐÑ£lfß¶*WŽÁ:"æÍ#€ìì ß„’ŠôtþØKGùðØ=6–™ªaÃÈÚšOÚ?qB,ëÙ—/ùJwwc³ñ €J”ÐWjݺu\ºtɨÙsE2aôÎ5Ê@¯¡I“ônj  Õ®-Ňh®%x±bF-dŒk“\¦Ìûƒ£ªUr'6ž¨(¾·ä”)do/îSÔ‹¼d•*Æ6EÓhÈË‹¾UJ”( B¨Ê«ìLý÷_>YÇöì!€Dk&˜7Ü礋‹©«ûs'=/˜«X17woÁyôˆ|}©zõ÷ѳT)QÚ$ëK` 99QË–DDññôâ…ˆs=~L*@^^dMíÞÍo è™Ì—ššªP(¬­­ÓŬõ’L¥)0Ð{£¢ø, ±«ârÛX˜3‡™€lIN¦† ù–?yz+ÊITTæ6É… ñm’ÙæŸ¥¥ÑöíDDoÞP‘"Ôµ«è–ºò¹wŸ}&À¡…FCžž†A‡‡‡([¶¬±rE2aÔH¸Ï½[·˜ à*+ f¹Û•-11T¥ Ô¡ƒ„Ò ,‰„“¶IÖÎ Î[XÌg[ž[·øf¸ stÆ?T¬˜g“ò×Wy9s@£F‘3’É0z4zõ‚JeȽ0$íT(š5CÛ¶ˆÇÂ…Ì4d‹‹ àêŠ#G0bk5„J…]»Ð¹3\]1`‚‚ S'lÙ‚W¯àïÎagÇRaP.^„B=ðÉ'°±€Ò¥Åôòe|þ9^½BëÖ DáÂÆ˜žŽY³`êTØÚæ~mÑ¢Ek×®½wïÞŒwL‘4 éäñ;ñ†õš]¹R/q &…‚ììÄm—k—.ñn‹œÝ˜ŒÁäâN,êV£¾lÝJÕ©C ©T&Úï:žÏFhÛV°}ƒÍ›ùƒ~]\BÿKoêÙ³gdd$-Z´À¸qã2.¸yóæ?þ¸bÅ aä‘´êýýiûvàƒƒùcP¶p•©Ã‡3–‘-RI ùù±–bž\½JcÆPÙ²ï£gåÊäëkT>¹à„…ÑäɤÕRRU«F šn''(ˆ  îݳKKã d·lÑñŽÝ»ws Dggç 6Œ7À¢E‹"##—,YR³fMU«VM´?–”¨1¨ÕääD EG³”ÁYŒØØÐ£G,eäÄš5|§5ÃŽòò'gn“\¢„‰Ú$ëKz:H°s'ÿW“qô(ÿ¸Ó¿¿órU‚Õ«ë>fjjjÑ¢E3ž¶‹/ víÚÖÖÖÜ;VVV§OŸL!I+Œúù‘—g.…½ÿéÓ ¯m5 ááü§}ïÞ ,X˜sÿ~æ6É•*1h“¬/·nQ‡´nÑ¡C´nŽi@³hC 냑; äâB€.#DJ¥òÃZ¢D‰XÑJc¤F¯\á×Ã9»­\)œ&CɰáJG¤ÉÕ«ää$‰ e“A |tì^¼8þ^3O¸‚(®´ÜÓ“ñ'_†1òš5¢ŒÏõ'3®ô¨M›6†Ñ¿ ðÕ)…Ѹ8Ú²…N2|.=B"§ä òÅìR^ëµµT>{Ä#«;1×&Y‚ÇîYIN¦áé|yJN&­–V®«1¨Žüðß)õÏ?EÿÍ>‡?(ȘaþøãŒÚ¦M¡Ôe‹”¨ñܼIU¨ÀZ¥¤ðv{»v±–’+7@J%íÝËZŠÐ$%±w'6†¤$JM%­–>ûŒ¬¬ ô"†w©°±Ñ7 I8Ï]£ÏŠß½{çääÀÑÑ1\dãq‰…ÑQ£¨CÃÛÍi4¼!íË—‚Ê2”ß~ãk«˜Ÿzå÷ƒkoOçϳ–"¹¸K­qL.ìÝK¥Kó;ÁÁtãc=j5Ÿ*ggGŠ5Kt4¿Ñtö¬ñƒ 0À2ñK,Œr‡>g×.¦a€¨TäîN`d\ª;Z-_5àâ»Bš)\›d.g›{yx0n“¬/ o¥DuêÄZ©TÔ»7ÿY+ª£8·ë*Ð3ø©S§7n¬×[batï^:pÀÀ²zna5i’pšŒƒë!5‹‘¬¨TÔ¶-ßâÕ+ÖjôäáCòõå­KªM²¾ÄÅѧŸ’³3¿j–HÂ\J uêÄ×qst‘'QQäèH ]¹"Èxæ¾I¬$F' €ot(4ªU‹Ó˜PèÓO  úõ³·»¹_Z»‘‘™Ý]\ÌãØ=+wîð­9½½©lYº|™µ ÿHN¦ví ¢E…Šn92nœ„àú ±0ºauìhÔVúÛ·deE Hhõ·?ŸX#)‹‘lyù’O¥ìÔ)›#ìo¿•„A^BïNœQ¯éàÀÌX–,!¥’O;{öLôÖôº“@Í›óŸO×®‰;×óçdgGVV,›¯ŠÄÂèŒÐìÙF Âù 0©Ë Îbdî\Ö:tàî]¾“æ°a½GŽŽ‚ùЃ]jîÄÆóêßI'8˜hútÖ‚>æõk¾m~éÒtïžèÓIõè!úD" ±0zÿ>8`ì)ÇСCED²#ÙrêŸ!ôa›®É^óæŒ?u*íÞ­ëŹ´I6†x¼zE ’½=_u*µÊý˜~‡§lY£Ž|u$,ŒllÈÊÊü¶³‰HraT6m"€¾úеŽáR~ü‘µÝع“¬¬H¡xŸbÍù\Z[uHDK— Ó.[p0ÃçÞr¯*UÈ××+#ñP©hÅ Þ¡gOêÔIŠYüwåÊ&’7dˆ„ gôGba4$„ºv¥:þ8÷$")¤l1’-\–­-ѹsïc™19ƒk×ò…Ø119^š¹MrÉ’fyìž-£G@ß~KD’0¼ËʳgTµ*T£†‰|¹ïß'¥’¬­Í7ÙNbaôî]¨zu£Ñj©hQ$×O³GhÄÖ:tfÌ~/‚ó»ç^&8Ú–-|-¦“S6_}õ*³;qÁ‚¼;±ôë5óäøq~‡äÁòò’nÁØ£Güc­Z¦Ë{ë×8ÐDÓ‰€ÄÂhr2íÞMÆ·øïÐÞ›[:Ü¿Ï[ŒÜSÕĨÕüw’[Br¯Zµ jÆ÷ƒxy½?1QÒîÄ‚ðô)Y[“µµÔ·#îÜá›~5lhº²ý{÷H©$[[)nnèŒÄ¨PÌKÃZG$€¾ù†µŽ¼xû–öì¡áéR¥÷4£°RßuÊþý|îÕ±£Y¶IÖ—'O¨OâҿǧŸ~’ôÃäêJµlI‰‰¦›·W¯lÒBÌ é…Ñ!C¨qcc(ŽçÓȥƓ'¼Åóél9uŠ&O¦ Þ¯ ³}éµÌß¿Ÿll>º½NlŽLplb¾ûŽúúkÖ:tàâE>ÂÛÛ¤Y«×¯“BAööæt!Å0Z³&Ææú¾{Ç?>K'“9ƒï¿'€ºta­#;ââhåJ>ñ6—×!w¼}ûvÛ¶m?ýôÓ™l3óOž|¿ÞÌôrw7ƒ6ÉúòîÍ›GC‡½xAC†È½…àìY¾‡K×®¦®_èÒ…úþ{“N*Ò £'OÒéÓÕÚ·'H©‹H/ŒnÙB-[ ÐXûÏ?%ýìÌ¥d²–¢\ÑW_}¸Å¹±~ýœ§-— bóAzaô§Ÿ É“'4”ruB“ÌŸOÕ«'i‹‘LDFÒ¼y\^á>›œÂ(€y>>´s'ÍŸO#FPÇŽäé™ãþ€¹”ueåéSêØ‘¼½‰ˆÞ¼aé.g~~ü)âøñl~9‹ïÿýÁÔ"  ¢\~ŠÇQ½:Ê•3v¨R¥…ÐP¸» ¡LPRRP¥ ""°gºwg­F´Z=º¹S§!9ÿä4oÞüÔ©S™ß}óÏžáÙ3EXúôÁŠP(Ä•- (SqqpwnÞDÙ²¬5éêU3DðõŬY œ<‰V­P¤ÂÂàìÌ@€à°ŽãbÂÕÞ04òÎÕ« i5ñÔ ++«\~¨Z¶l©ÇXoßšúpæN%:vŒˆèôióËr]ºTDsyážYÀ–ÎäöËÀ†°0tê„þýªQ#¸pA€¡ÄàÛoámk)zãœë"¢aÆz[[c‰MJ ž<ggh48wš5C‘"LeéÉìÙ˜0V¯ÆäÉl4üóΟGñâ¼Ë€uÏBx8T®œCqíéj×`(‘øã¨|y³ë7ÃbdÅ ÖRôC£ÑT«V-p⃵ IDATÛ0ºzõjÖêB«¥C‡øÐéæFSt4kM¡ÕÒ¨Qµ5mÛÆR çQ¢Dö.5f‹ô¨°|öÄZGÎìÝK0‹‘Ñh4>>>6Ù»¸¸>|˜µ.áèÜ™úë/"¢/X«1†/Kµ±!ÆJ¼¼ ¥KYÊéí8Ÿ}†çÏJâÛ£ºvE£Fˆ‰ÁÊ•¬¥è‡••ÕÖ­[U*Õ“'OÎ;—’’Ó¡CÖºŒæÞ=þ¦S'”. ;;(S†­(IOG¿~X¿vvØ·={²ó÷߸}nn1‚¥ 1`dz£Q#„q—ݱƒêÐA€¡ÄƒKE.\˜^¿f-%ßsâ)•T­©Õ¤V›÷³§JÅ÷Orr¢“'‹IOç[q[ÌžÏHr5ºz5.\@ Õ¸1œ?­V€ÑD¢ys|ñâã±hk)ù•˜Ì™µÍšÁË : - ÖÖptd­ÌPRSÑ­üýQ¨Тc=;vàÞ=T¬ˆo¿e¬D XÇqñáz²I¼cî•+|Ç0)íÁõë×ïÕ:uê >¼zõêNNN666nnn>>>w,£Ew|Ì-”, gJb"µhA+FÁÁ¬Õ©ÕT¹2´ak)¢ É0êçGMšöïÙ“Ú´I˜ÑÄ£[7hÔ(Ö:Þ“––æçç—FíííÇ¿sçÎýû÷7â6;;» )Ÿàå‚ZM«WóÝvî¤víèî]Öš„ >žš6%€J•’Ê¿ˆs™ô𰄨ìdýõW¾c‚ pV”\ H)#I‹‘+W®d„QŒ÷£££ííí¹÷Ë”)“jny¯DÿåH”.-Ŧ´˯¬Ë”¡Öjˆˆ(-÷w’l=¡ÑHroô«¯páfÎf´ŒíQ‰ãá¾}¡VcölÖRò¦xñâíÚµãþqäȶzôàäItíŠädt邾}ñë¯øïóÀ쉌Dóæ¸z•*áìYäØkj6oÆÓ§¨^}û²–"’ £¥K£aC/.ÌhuêÀÞ!!xóF˜ÅcÎ(€mÛpó&k)yS»víŒ?ŸãŠ#¥¦LÁþýX» ¶mÃW_™SW”\ˆˆ@«V¸wUªàäIT¨ÀZ %sçÀ¬YP*Y« I†Ñ§OÑ´)Ú·f4Ô©"\¾,Ì€âQ¾<¾ýZ-›¾;zRæƒTʰ°0†JòæÅ ô뇅 ¡P`éR,Y‚‘#Yk”°04mŠû÷áå…3gèŽ&ë×ãåKÔªÅ8eUd$Fííq{®—r~ÿû±oŸôÕÚð,œ˜˜ÈPInh4p÷.¶nŲeP©Ð¤ &Là“ê-ƒGв%ž<ÁgŸáÔ)”(ÁZÐ$'cÁ˜5ËB–ü9 É0êâ‚S§ às"w¬,ýíQ%Kb̘1ƒµ”|¸Òô¿É)) Àÿ–&%%KJ+×G 6oÆ AÐh0i–-“h&fTV¯†BŸ~b-ÅtH5Œöè[·ðóÏBŽivÏõJ%ÿX4o’’X«Ajj*k @J >ù:àáCT©‚°0üù§Dа¬X¡C¡Ñ`Á,Z$Ýò‚HJB§N¨[—µÓ!Õ0Z¤¼¼ l6¢Ù…Qݺ¡aCDEaÅ ÖR`º3÷¬a×.<|{{´k‡zõ’˜­·‡¾,Y‚qã@„_~afŒ¬ /^`Ý:XYå«¥( Ù“úˆª]›š7rÌØX¾5²yã;F9;3±Éé¤>[Ž;öÉ'Ÿ¸¹¹ùùù¥§§ÿüóÏJ¥ÒÛÛûžñ=³çÎ%€ºu#"JI1v4ó"ÃyÍÖRòbÄ諯Xë05R £‰‰££ÀÃzx@W®<¬Ø´nMM›fâiU*ÕŸþ™FÝÜÜnݺ¥2å‡Ð4w.QDU¬H7šnj‰ðã¼12×^ZÊ<~L66de%•^Ñ&Dªa”ˆ‚ƒéñcÇ8ÐMáéòeR(ÈÑ‘"#M9í Aƒ²>¾4kÖÌDÓÇÅ‘“)té‘Ex{è…FCÇóÆÈÛ·³V£ƒ@>>¬u0@ÂaT Ö­#€úôa­CºtÒ@ÊÄÄÐøñtù2‘¯/O11¬5™††%€ììèàAÖjtàþ}R*ÉÚš=b-…£ýúQéÒü¯“PܾM•//䘦áÎR*ÉÆFøºÔ˜6jÝšµv¨TÔ»7doO¬Õè†4hklêI=€¸8¼|‰—/…ó“OP¸0ž>ED„ÚOOÞbdÎÖRD@£ÁúõèÓ&MB÷îø¸2*‘šŠ=°c ÄÑ£øÏ©EÒܾíÛak›_*è³Â:ŽçLX={FiiÛ¦ ´{·ÀÚ€ðp²µ%¥’,ÃÓøCbcÉÙ™:s†µ¦$'SûöPÑ¢?‡‰ g¾;|8kÌðj´bE”-+|Ÿ]sÌå¨POÀÊì9gΠqc;†bŰlüýóOù`6$&¢];ÀÅAA¨_Ÿµ ݸq»wÃÞ^úÆÅCÂatûvT®Œ©SÖ¼:æebút88àï¿qñ"k)ÆÁD]º„ ðë¯0p zö”nqŽØ¼yƒÖ­qú4J—ÆéÓNÿÖ<ñõ¾û¥K³– ‡Q­Cðþ@ B©ÄµkBi£¾”*…ï¿ÌÀb$GÞ¼Á AhÞD=+Wb×.ÖšX oo\¹‚²eqò$ªWg-Hg.]â»N™ÂZ K$ÙþêqqˆŠ‚›œœÙË wîàüyþß¼ˆ‹ƒ»;Þ¼ÁñãhÕŠµ}ˆ‹CáÂHNF•*xý/šÓšK<^¾Ä_ $•+#(å˳¤íÛãèQüð~ù…µ–Hx5êìŒjÕ„¡0+£Ð¬8;cÂ@ê#™Y·+b÷n8:bëV„„È1^¼@Ë– §'Μ1³zú4ŽEÁ‚’.ó7 £oÞ F |ò‰ð#›ï)Ǹq(YW®àÀÖRòB­Fh(X[#.\ÏüV­P©[]’àñc4mЇQ«Nœ@É’¬é çU7v,Šc¬„5~¨×h`k …ii·§}ðÕª¡tióËÍ`åJŒOOܺ+©~>~Œ¶m¡Tâî](Fƒ¬5I†»wáíÈH4h€€ók–zâZ·F‘"Gá¬Õ0Fª¿”J„†":Zø0Qµ*\\ðò%ž>xd“1l*UÂÝ»øë/ÖR²ãòe¤§£|yX[#=Ož@©”cè{nÝB«VˆŒD“&’3—×îsüx9†BÒa@ÅŠ(ZTø$… æü\okËÿϘ•еš; à÷ßamÇùÙ .]B‹ˆŽ†·7Í2 =ŠóçáêŠñãYK‘Ò£ß|WW|`B)æ¾=  _?|ò ž<‘ˆÅÂÃqâ4ogg¤§€»»ðf͹shÛoߢK<(9cd] Âôé0q¢('Àfˆ´Ã¨Fƒ˜Qv0¹0j¦IøJ%__?o’“‹¹yÕªÁÇïÞ¡{w„‡cÄÆ’$ȱchÓññøê+øû£@Ö‚ âÀ\½Š%0jk)RAÚatÅ DF¢{wáGþì3X[ãæMöȺwGƒˆŒÄÊ•l¤¦bõj¤¤ fMÔ®¶m‘–…ÎÎlôH™ýûѹ3’“1`vì0×EºVË/E§LAÎŽ°ùÖEýì¨S‡:uеã ä-FÞ¼a0û—_@ å?o½Ø½›lmùޱZ-k5FàïO¹¹ÉÿÝ"íÕèŽpsøq¢ nÏõ¼½Ñªââ°d‰‰f$ÂîÝøýwà¿Ó$î¼ÎÎÎDÌŽ-[ðõ×P©0~³"í½Ñ¤$¸¹‰XãÁmê™ûö(€5ЧT*Ì+ä°±±˜8‘w†˜?ãÆñ]QdòdÊøúÂÊ k×ZBbPZŸ]7}ºÀ•Ù–ë8žvvPR’(ƒÿò‹å˜dXŒâέ8®\áw]ß¾`Ì|‚VK£FñæòÛ¶±V#¿ýF}ò‰¼Íi¯F„†"5U¬b³î˜—‰ 0dˆ0#›7£J¼xzõ0w.Ξ•ó@uE«ÅðáX½66ض }û²$))üSάYòR4{XÇq¦¤¤­-YYQ|%LP«áヿþ‚“б#kAñî~þfÍ2ãŒW‘‘|ÕhœŒèh±Æ·¤çzS§¢Hò]BtáåKppÀ•+ DR*WF¯^ò¦¢[7øû£P! E Ö‚„cõjÄÄ AtéÂZŠt‘|]¼qq:t@p0J•Âýû8xÐ\[^Jˆ4oŽ7P¥ NžD… ¬ Mt4–/€yóXK1$F­­Q° ¸SXFǼL €êÕŽéÓqï”Jtè€ nn¬õ™3aahÚ÷ïÃË gΠ\9Ö‚D`ñb¼{‡víøg5™\‘°Á2Gz:\]‘˜ˆ´4±œ„Õj8;#%±±(ZT”)˜°{7zö€–-qâ’“am-¯@åÑ#|ñž=Cýú8zÔ¢~`2ˆˆ@•*HMÅ•+–vh&æ°U(žŽ·oÅšÂÆuë‚—.‰5…‰yò  GþwÀÖ äj,·o£ys<{†Fh™1À/¿ %;Ë1TG$F„…A£A±b"NaIÛ£j55ÂÔ©8z?ý—/#!µ,óçÆ ´n¨(´ncÇ,¶ÏÀóçX·VVò®¨î˜C-\ééP«EœÂ¶GSS±lΜ &L€jÔ@Û¶hÙoßbÙ2ÖúÌœ в%bbж-°ä"…ŸFZzô€—k)æëŒ+0€Ú¹SÄ)^½"€ 4ã>`\ÿˆúõ3÷à,Fœœ(*Š‘2óçøqrt$€ºu£´4ÖjÄäñc²±¬Ýb¾ÁV£ŽŽP*Å},uu…»;q玈³öìAß¾ °aèÒ d®…ÿì3tìˆwï0>#•fN` :wFRúõî]¾¿a-Ŭ`Çu 99ûjaùæè·ßDŸH@’“©LhÏžÜ.»u‹· 3•2Káï¿ycäÁƒÍøIEGBBH©$kkK°Õ1-æ°µ·‡B¤$qg1£S¦tè€;`o… ±j¾ü2·ë½¼Ð»7T*ùÐ@?¶nEÏžP©0f 6n´üŽÅsçB£Aÿþ¨\™µsƒu×ÈÆ†ºvw–ë×  Ê•ÅÅH¸Ñš5P:zÜøè¿çuïžHÒ,Í›I©$€&NÌíŠoÞ$++*P€žSÌ¥;ïÞ‘JEj5U¯NJ%;fà8#ÁÁ‚ê³8/æÍå.d-ÅT\»F ÙÛÓË—¬¥˜%æ°U*ag'új’lõ´o<<°i¬­±y3nÞÄ_8T©R9Døßÿ•hYL™‚I“ P`Íüø#k5¦Â×—Oö(Uе³ÄÂ(€¢Eáä„ÔTqg‘Ô)SD¤¥!"‚·¢jØžžF9e Æ?ÿàäIZ“'cáBXYaÝ: ÎZ©¸t ÂÉ Ó¦±–b®˜IutD¡BxýZÜY5‚•®\á›Ë±"6M›¢A$'£W/:”[{½(VŒ·‘íê2¡ÕbäHüò oŒ²yùÍ›ãÚ5¸»ãìYT­ÊZ ´Z~)úã°·g­Æ0“0Z§RRpø°)æjØJ%®]¦hêéS Š/P¹2†åëˆIt]k×-Zàõk,YÂZŠIxñ­Z!$žž8s&ÿöàØ½wî lÙ|T©%6¬‹úuF¥¢çÏMÔ²¬fMèÜ9†êÛ—:T€¡ÄàìYò…ÅHh(•/OÕ¬I¯^±VõšªV%€Ö¬a-År0“Õ(WW”-+¢Íò‡ù\ŸšŠùó1~<øú¢O>ÉY‚4iÂ[Œ,\ÈZŠ˜Ü½‹fÍðô)4À¿ÿÂÕ•µ vlߎ‡Q©† a-Å‚`Çu¦Z5*UÊD6~~PÞ~ÿ>Y[“µµytÀå,FììèéSÖRÄáæM*Q‚jÒ„ââX«aŠJEîîÐæÍ¬¥Xæ³ ÁË—¨XÑsVº?jÕÂýûððÀÂ…0Ý7//ôê…ÔTÌ™ÃZŠ\º„-ðê¼½˜ßóÌ·lÁãÇðð@ÿþ¬¥Xf•~ S¤¹¡D ÄÄ <*ä}}j*ìì0|8Ö­ÃÈ‘X½Zt…Âòè<=¡Õâöm‹J:: >]º`çN(ÀZSÒÒPµ*ž=ÃÖ­ðña­Æ¢0ŸÕèˆ(Qüaй 4lè°=úì¾üß|3f`ùr,_.º<Á©RB£ásò-ƒ  ´iƒøxôèÿüClÚ„gÏP³&úôa-ÅÒ0Ÿ0êê gg¤§›hº—ÔjDG#*ÊDÓÕ¯ܼ‰wïÞ¿™œŒçÏ@£Aj*N€ÎQ¢„‰T‰Ê”)(Tø÷_ÖRŒ`Ë|ý5T*Œ‡õëå•$&âçŸ`öì|árjzXÇq9}šjÚÔt3Ö­Kýû/ÿ×+W¨lYjÝšˆ(>žnß6“1kŸd¦lÜHVVÐÌ™¬¥H‰ùó   Xë°XÌ糺D +–} °HÉiO\æS¥Jx÷¯_ãí[*„5D™”-'ÂÕçÎáÈÖRôgùr|û-´Z,X€Ù³Y«‘ X¼€ü=ÖqÜ8nÝ¢þýÅÚÿúë/¨dI(0ˆ($Äò÷Ú–,!€¼¼Ìì_:{6¤PЪU¬¥H î;óùç¬uX2R]¾{‡iÓpûöGoÆÅ!<œwJIÁŒ¨_åË‹²ÿu럠š˜ˆR¥˜ÕªYþ^ÛÈ‘([·oÃߟµ™2¾¾°²ÂÚµ5е)ñæ –.ÀÓˈë8ž3Ë—@“Ÿ%%•)C=N|M›•…‡ ?õÁƒdeEõêñ3Þ¼)üRfýz¨JR©XKÉ ­–F"€¬­iÛ6Öj¤Ç´iP«V¬uX8£j5ÕªEäìL£GS:T¦ µmË¿ P»vBÎG+W’VKÉÉT¡ F]»@~~BÎ"}ÒÓ©Z5hýzÖRrE£¡aà ڹ“µéñê9: Ö«L&g$F‰èüyþà5ãÅåf¼þþ[°¹´Z¾?ž¿?QJ ÑâÅаa‚Íb.ìØA•.MÉɬ¥ä€ZÍ7!´³£C‡X«‘$“&YH"°ä‘öN_£F™Ûy}hU_ª:u2vŠôtl؀Ç¡P`Ì´kà?oÓû-K„^½ðé§xùkÖ°–’j5||ð×_prB@:vd-HzDD`Õ*(˜;—µ”|ë8ž±±äâòÑ 4ã5mZn7._®Óø[·@¤VgóÕÔT*P€¬¬òcƒµÃ‡ ² g6 IDATŠg-åcRR¨cG¨P!:}šµ©òý÷P—.¬uä $Fé¿H—é¥TÒ³g9Þ²iÕ¯ŸÛ˜/ÒàÁ¤V“ZMmÚŸ¥§ge£Fïžò-Z@¾¾¬u|@b"µlI+FÁÁ¬ÕH•gÏø‹,‘æF‰¨U«Ìa´C‡/ £B…¨fÍ/HO'hƼ§ž0š=ÛÙæÎ™3¼ÅˆD\7âã©Y3¨xqº~µ üõêÅZG~AÚ{£¬Y“¹ÑÙ·ßf¥Fƒþý‘!ݳg<6@©Ä¢E˜=½{ç=u¾Ýд)Ú·—ŠÅÈë×hÝgΠLœ>ÚµY ’*aaؼÖÖò®¨é`Çuæ‡Þ/EK–Ì1¥‘« ¨\¹Ì_Úµ‹*_>Çç÷l‰ˆà3®Ì«ªG(nÞä-FrÙB1ÑÑT»6T©’(™Â–ÄÀP¿~¬uä#Ì'Œ&'S¥J|ˆœ>=ûk®^}ŸU¢‘ZMË—S:”œLZ-MžLë=5ç(yçŽQúÍ—¯¿&€¾ý–™€/ø<Ö*U,Ö0J(BBH©$ e-%a>a”ˆöîå+—² … |i÷*\˜ÒÒH«å5ýù§áóöî­ëFªEòð!Y[“RI!! fü˜*VäËü##0/úô!€† a­#a&{£]»¢sgjÙ•*eóÕÿý¿ÿkB–,BÕ«Èû|F~ÞÅ#¦oŠ–-ŽÚµqü8J–4µóâÖ-ÞrjæLÖRòfciwýúõçÏŸxõªà“'¯êÕ+R¤H½zõœ2ìíÑ®]æŽy®® ƒ££±s£~}T«†c‡2S^¾DåÊHMÅÕ«øôSMzç¼½…FpäœM4¯ùòÕWسÇ,MÍó£ÿüóORRR¦7 EóæÍ‹+†×¯áå…ÈÈlîôðÀÖ­¨WϨéÕj8;#%±±(ZÔ¨¡Ì— °l:tÀáæ˜îÆ ´m‹èh´j…ø,´x®\Aƒ°³ÃãÇ(Uеšü…<Ô_»v-k @D¸íáó¡<@£F˜7á llP¯ˆpñ¢áƒ˜;Ó¦¡P!9Â[§ˆÊÅ‹hÙÑÑhÓÊ1T'æÌ†—c¨é1ƒ0úœ³?Ê•J¿bvïÎíþôt̘æÍn¸®~¾Ýàâ‚ñã`útq':q_|¸8t놃áà ît–ÁÅ‹8t bÚ4ÖRò#R£Z­V“óBÒ1*ª`¦Ÿ++)‚"EP¡*U‚—êÖEãÆppÀ¤IxøÐ@Ü)ç&’o™4 ®®8{bMˆÎ‘”„o¾Á®]²1²®øúÀÈ‘pqa-%?"õ½Q•JuèСœ¾jóî]ùB…j6lˆ`k+âÓ_l,\]áà€¸8X[‹5‹ôY²“&¡fM\¿.¼ÀÞ½èÝ* â‹ÍdtáÔ)´hB…†bÅX«ÉH}5jkk«ÈÙVíädï鉒%Q¤ˆ¸;h..pwGRîÜqé3jÊ–Å­[yl¤ÀÖ­èÕ *ÆŒÁ¦Mr Õn›eÜ89†²Bêa€sΙ. …¢bÅŠ&Ò!o°³ãi§OGzº`Ãþþ;Dz:&NÄòå²—ºáìY-Š XKÉ¿˜A­_¿¾UÏÖ&{ÄÎçIø ‚jÕðèüü„påJ  `ñb9†ê¦4a f­&ÿ"õ½QŽ·oß^¸p!õƒ¦M …¢ZµjÕ«W7ˆ›7Q»6ÜÝjºI¥ÉöíèÛeÊàÑ#ØÛ5ÔÒ¥˜4 DX¸?þ(¾|Ñ#èØ®®xü¥(2&Ç<Â(GtttTT”J¥*R¤HÅŠsZ¢Š…V‹"E€ÈÈü^•H„ºuqý:–.å³  cÊ,\++¬Z…#„Ó—? B½z¸v ‹aÒ$Öjò5æFÙãí  ìÛ‡.]XKaÍ¡CèÜ..xü… 2BF ]·C‡ ­/°w/ºwG™2 å­Ãda{£BÞÍ S'4i‚ØX,_®÷½Z-FŽÄÂ…°¶Æ¶mr 5­3fÀ?Ê1”9rÕ9 ÿC,€E‹­Ç]Z-†çí þþ['™¬øûãî]”-‹aÃXK‘‘è^4j++äóœoiÚíÚáÝ;,Z¤ë-ééðñÁ† °·ÇÞ½èÜYL}–Kz:ß ïÿËl®#ÃyoTO<=qï._Fýú¬¥H€«WQ¿> ÀÇ([6‹ÓÒг'DÁ‚8xŸn‰–È`ÀTª„û÷acÃZŒ¼Õù¹þCêÖÅW_!5?ý”Ç•))|«‘Â… ÇPÃQ©ø ú3ä*ä0ª'ò)S&æÍƒµ56oÎ-61íÛ# ..8qMš˜PŸÅ±e žcTFzÈaÔ ¸0šq*-„6mnÝàîŽGðǬ5Y ‹#>­[£iSÖRd²G>b2”’%ñêÂÂ`2O=ÉràzõBZ À¦Mع>>(WÊkRc‰ŽF¥JHNÆ¥Kr7É"¯F ¥aC@~®öìAÏžHKÃ!ؼJ%z÷FíÚxö kײgþüò ’’о½C¥ŒF EÞ°e ¾þ*ÆÃ† |i•æÌ€yó˜ÈV yÕ«¡P`î\ÖRdrC£†"wÌÛ´ ƒC£ÁÌ™X¶ì£œðÎѸ±#2,X€ÔTtí*÷s‘8òÞ¨¡¤¤ÀÙZ-Þ¾ÍÞ¶Ë—cÂaÁ>]4gΠys.ŒÇQ¬˜Éõ™?OžÀÃéé¸u žž¬ÕÈ䆼5{{Ôª…ôt³–bræÎå}•W­Ê>†hÖŒ?»_¸Ð”Ò,‡ùó¡R¡gO9†J9ŒAþ|®Ÿ2…ï0´f FÊíÊŸ†B•+ñâ…©ÄY ã÷ßamÍï2ËH9ŒA~;e"Â?ðÆÈþ™·'eݺèÑC'‹™LÌ µ}û¢jUÖRdòFÞ5‚gÏP¾<ŠCLŒå7ÝáÌå×­ƒ ¶nE¯^:Ýõð!<=¡PàÞ=T®,²DK!$^^P*ñà*T`­F&oäÕ¨”+77¼~GXK™ôtôïuë`g‡½{u¡ªVE¿~P«1k–ˆò,Œ9s Ñ 9†š r5. ß²·GÕjøø`Û689áÈtì¨ßí³f¡@lߎ7ÄÑgYܼ (ÙJ@FÂÈaÔ8,~{45ݺÁß… áÈ´l©÷åÊaØ0hµ9zÞÉ|Èœ9Ðj1t(Ê•c-EFWä½Qã¸xÁË ·n±–"))èÞG¢X1=Šzõ '&îîHLĹs|A™l¹r ÀÞ¡¡²e€!¯FãÓOag‡»wÏZŠÐ$$ m[=ŠâÅdx P¼8ÆŽþ³‘ɉٳA„áÃåj^È«Q£iÒçÏãŸ,ª¥îë×h×ÁÁ(SAA¨VÍØ3,F,ì% Ü“MÁ‚ ƒ‹ k52z ¯FÆò:áÇÄÀÛÁÁ¨T gÎC.Œ~€iÓ rg ·w¿übÒy%Åθ{*äÝ[FÚÈaT Ì+ŒîÚ…^½ Ráûï±i”J8‹‘+ò©ÅHz:|}`êT“>Ȉ€F¢qc(¸tÉ Ëÿ}ú@­Æ„ øõWf}ûëÕC·nHIÁüùl°eÛ6 |y|÷´Zþ¼%?°až?G­ZøúkÖRd„AÞ­E‹">‘‘¢ôõ0 "Œß~ãÍå{÷f-( #çÏó+z &9•+#2{ö {wÖjd„A^ ‡•>û .^d-å?´Z †ß~Cøûo)ÆPÅ‹ãûïüa1²f "#Q¿>ºuc-EF0ä0*(’ꄟžŽo¾Á† °·ÇÞ½èÜ™µ œùñG-ŠÓ§ÄZŠ˜$&òå[3g2Ë3“9Œ ÷L*…íÑ´4tïŽíÛQ° о=kA¹’a12uª%[Œ¬\‰ØX4lˆNXK‘yoTPââP¬lmϲ4%%=z … ãða¾?¿ÄIIA•*ˆˆ°ØM÷oQ©ââooÖjd„D^ г3ªWGj*nÜ`¦!1íÛ# ..8qÂù„c°±á³G}}-Íbdñb$$à‹/ÐôÿíÝiTSgð? ¨€ ( Š:Pè *(j±¸¡ÕV­ZY .­(޵êPq9S÷AGbëÂXÁ¡îÔŠ¢ ÒQÇR°ÊbŪ¥(”Ý$d>$!E̽77y~g>¼Ü$÷þ§§}Î{·÷y‡ë(DóèÚ¨¦ååá­·àà€Ÿfõ¸Ož`ôhܽ‹Þ½‘š GGV®)õõ099رŸ~Êu yö ½{£ºׯÃË‹ë4Dóh6ªiÎÎèÒ±ºþ[q1FŒÀÝ»puÅ•+|­¡åûõk×êN‹‘M›PU…ñ㩆ê**£šf`€Áƒ/æçÃÇ÷îÁÝ—.¡[7–ŽËÉ“•-Fvìà:Š&c×.`íZ®£¦Pe›—Gú #F ¨ƒ!- 66l”iŠû0ºÑbdÃÔÖâÃyv»¼*£ `­ŒÞº…áÃñè†EJ ,-?";F¨Q(+ÃæÍ\Gy3……øúk4Õmt‹‰UU°°€ÊË!1u”ÌLŒ‡/0z4NžÔµö¼ÙÙ4¦¦¸vv\§i¯ˆ|ý5fÎÄáÃ\G! ¢Ù(ÌÌðç?C"ÁLâ?ÿŸ^¼ÀĉHNÖµ ÀÓ“'ó»ÅH~¾²W MEu•Qf0z^ñ"üüP^Ž©SqäLL9 çÖ­ƒ¡!¾ú ùù\Gi—µk!‘`ölôíËuÂ,*£Ì`®Œž>÷ßGUæÌAR’.7•tsS¶áãl.7  õ®?Š^¢2Ê Å+¡ß¯áÝ?ŽéÓQW‡°0ì߯û-(-Fpç×Q^Óš5É0gzöä: a•Qf89ÁÖ¿þŠ‚íóàAesùÅ‹•÷u^ÏžøøcÈdøâ ®£¼Žœ|û-LLÍuÂ=øO‘+ÞÞ€æÎë÷íCh¨² ÄÆêÑ¢¿ÑÑ03ÉZÔSà­Y¹ááèуë(„ TF£ÁË£Û·#<26làå…Â7ak«l1—™]f&Nœ€XŒ•+¹ŽBXBe”1­­˜W\ŒÊÊ×ØÏºuX¼6oÖ¢ÆÈlúüsXY!5©©\Giƒ5k`þ|Þ¿•KÚŒÊ(c„PˆlR4/\À{ïÁܼÉ7KJZÝÉòåXµ vïÆÒ¥LEÕrøË_>´¹zgÏ¢C½hÏGþÊ(cD"xx@&CV–rËž=˜0..M¾&—#"¢…ŸËåX¶ 7ÂÈbî\Æk³E‹`k‹¬,œ:Åuµ·Â>ý]ºp…°‡Ê¨æää4_ÛMu^/•báBÌ›‰ï¾Ûä;ÙÙ8y÷ï7ÙX_ °y3Œ‘€Ù³Ž®õÌÌð׿@t4d2®Ó´"- ©©°´Ä²e\G!¬¢2ª9¿ÿ €Å‹qú4ÊË•w™ÒÓ1~^È{ö”×ÖråçÏ˹••¼¼œë(„m4Õ¨DE)Ç2™²?hã“ÐáÛ<òyñ"~ù®\AI jk1e ’’б#ΟǸq¬燀¸¹¡¨{÷r¥)¹\yÍaéRtìÈuÂ6*£š¶y3üüZý´Ù…ÑýK9Épê>üÉÉèÜ©©ðña0$O*›ýÛßPUÅušFΜAv6llÉuÂZo”2¤å×Ào߆››r\] [Û†»R;£´]»âüyôïÏRT>2×®aýzmy¨¨¾¸u [·bÉ®ÓPeFa!¼¼PZÚd£µ5ž>m8©?zÓ§7ù‚XŒƒ1u*K!yêâEŒ äçÃÊŠë4À±c˜6 vvxð¦¦\§! “zfôê…ÇadÔdc³ £ ÍU]iÓàá-[Xm,Ê/£GcäH”•aëV®£õõˆ‰€åË©†ê-š2iýú&/VoßÞpíìùst놗/[ý­@€áÃñÑG˜6Mwš,iJV†XŒ`kËe’ÄDÌž^½—§Ëk¿µh6ʤ+ÖðçÈ‘ ã£GÕÕPööpsƒ£#Äb¦âñ——&NDU¾ü’ËR©rUæ+¨†ê3š2¬º>>øïѹ3~ýµa‘ÐwßEzz ßwwÇäɘ4‰úñþ;wàî##äæÂɉ› ññ AïÞÈÍ…±17ˆ 2ʼŸ†—†ʼn [zölXeÃÐÆ)«'WqèæÌA|<Gùú>Ä?ÿ‰  ­A'õ̺|ùòÿ÷êêŸ9ãèèúûï¿#1r9D"Lœˆýûñô)þýoDEQ }=ëÖA(Ä¡C¸{—ƒ£8€‡ñÖ[´â¡Ù(ƒ,X°{÷nÅØD"Qáܹ6ÇcìXºîù¦>ù»vaÊ;ÆêqkjЧ~ù‡cæLVM´•Q¦?~|j+O€vîÜù·ß~c9nzò}ú ºW¯*»¶°cÇDF¢_?ܼ©G ]H+褞)ËZ_-­´´ô›o¾a3ŒÎêÖMÙbdÕ*öZ]­|B &†j(•Qæ<|øPͧGŽa-‰Ž[¾––¸p—.±tÄ]»ðô) ÂäÉ,‘h7*£L‘©]]øùóç¬%Ñqª#Ë—³Ñb¤¢74% ¨Œ2ÅX탄ööö¬%Ñ}‹+[Œœ>Íø±þñüö† ÁøñŒ‹ð•Q¦¼ýöÛj>«ç½•4ËÌ +V@t4êë<Ћز€Þµ¹&jQeʾ}û‚–ÿñöë×oĈ,çÑqóæÁÉ ·o3ÛbdÛ6”•Á×£G3xÂ7ôÀƒN:5cÆŒ—Mßwww¿~ýº)­¤qŠW3{öĽ{Œ¼á^R''TV"#Æi~ÿ„·h6Ê I“&•””DEEy{{»¹¹M˜0áÛo¿ÍÉÉ¡ʈÀ@¸º¢¨ûö1²ÿ­[QY‰1c¨†’fh6JtˆbånÝðà†ß{ö ½{£º™™ðôÔäž ÿÑl”è)S0x0ž<ÁŽÞóÆ¨ªÂ„ TCÉ«h6JtKJ ÆŽ…… 4¶Üuq1úöE]nÜ 6YäU4%ºÅÏOÙbäïר>ׯWö¾¦JZB³Q¢s23áí ±ùù°±yÓ½ÂÙ2~ü±¡«+!Ðl”3AAA 8pþüù®®®:t …wZìÒLÔ4￯±#_~ ‰þþTCIkh6Ê™—/_>|888Xñ§H$š7ož···©©é† ®^½ ÀÔÔ499yÔ¨Q\å£Û·Ñ¯ŒŒ—‡^½Ú¿Ÿ{÷àæܽ‹¾}5—è*£\ÊÎÎöòòRŒóòòã’’GGÇššvvvùùù&&&œ¥ä©€$$ $û÷·'AAøæãÀÍ%#º†NêµQ×®]ǧ?~üøìÙ³Üæá%E‹‘ƒÛßb$7‰‰ •í? i•Q-åáá¡ÿý÷&á«^½ ™ 11íÜÃêÕÉ GG&#º†Ê¨–²³³S 8LÂc«VA,Ʊc¸~ýµ›“ƒ#G`b‚èh’BeTK‰D"Õ¸¢¢‚Ã$<Ö­>ùryË-FTí ÎËÍ?]½r9""ààÀlHÂTFµ”T*U…¯¬W”––æé陜œÌn(Z±––HIÁåËM¶çåaÉ帠³g7Y9?3'OB,ÆÊ•ìE%¼EeTK•——«ÆÖÖÖªqAAADDD\\Ü7¸ÈÅ7––ˆŠš¶‘HÜ0•Épîvíjø•âžÒ‚°µe1+á+*£Zª¨¨H5îßèDKK˸¸¸Õtï¸í¢¢`cƒÌL¨&ï«VáúuH$Ê? æ/]Š~€ôtœ;‡ðùç\Ä%üCeTKedd(`r£”–––­-ªOZfn®l1²r%êëqù26mÐPFÍkk1u*Ê˱f ,\ˆ.]8ÉKx‡þƒÔFW®\ÉÌÌTŒÃÂÂzôèÁmÞ›?½záömÄÅaæLåôSÕ•@Õõ Ó§ãÒ%XZâ³Ï¸‰JxȈëD©°°pìØ±NNNR©4))I±Ñ××766–Û`º@(Dt4ÂÂðÙg¨®VnlvR¯páxzbÏ告n'Ò¥RÒ"*£Ú¢¦¦æèÑ£eeeæææC‡ 744ä:ßÔ×cËìÙƒúz(îÔI$¨¬ÐPCñÊI}c.(ë©‚¥%¾úŠj(i •QmaooŸžžÎu `Ù28;ãã[x TEMmløp:DO5èÚ¨¶¨­­å:‚n™4 99ê:!«®¶ÖÚ^(ĶmHK£JÔ£2ª-dêçD¤ºwGJ öìA£W¨ŸöîŒ ,Z@'õú9900hxÿÕ;õ*³f!.;²—“ð•QÎH$Õ£ªªªnݺåââbll¬æWÞÞÞÞÞÞ̧Ó-®®ÈÈ@dd“eC[¼Sob‚M›°p!MBIÛÑI=gæÎ¨ú³¸¸ØÝݺâxÁwíIDATgй9öïGR,,”[^=©wvÆÕ«ˆŒ¤J^ ­~OôÌÇ@Fe]²±±˜3;wÂÜœë|„h6JôŒ£#ÒÒ††Ö+—-KMMEÇŽ8~ññTCIûÐl”è—ãÇWTTx7)ÐQ,Þ¶sgHH×Ñ_Q%z$%%eܸq-þ;Ÿ˜˜8kÖ,ö#@e”è[[ÛgÏžµøQ§NÊÊÊXÎCt]%úâÑ£G­ÕPåååYYYlæ!:ƒÊ(Ñ×®]SÿêÀJÚ‡Ê(Ñfffê¿ jñQBþ•Q¢/|}} Ô>W߸ˀBPPA#œ?¾««k‡„B¡ƒƒC@@À;w˜LMx€Ê(Ñb±xðàÁ­}êââbccÓlãÞ½{ãããUæææŠD¢Õ«W'$$xzz+©©© e&¼@wê‰yþü¹““S㮫 b±8//Ï¡¥ñ²³³½¼¼cgggÕ2%%%ŽŽŽ555ìììòóóMLL˜ÌN´ÍF‰±²²*..ž4i’P(Tl122òóó{ôèQ‹5T®]»ªÖzüøñÙ³g5œ•ð•Q¢_ÌÍÍOžÂ*£„´SFF†b ¿õÓO?eeeˆ‰‰ñóóËÉÉéÓ§7) ó褞ö¸råJff¦bÖ£GÕG111Š `æÌ™ÕÕÕ)))D$l¡Ù(!mUXX8vìX'''©T𔔤ØèëëÛøk~~~ª±D"-z¢ë¨ŒÒV555G-++377:th```xx¸¡¡ak?¹y󦱱ñ˜1cØÌIXFe”¶²··OOOoû÷%Illltt´½½=s©çèÚ(!mU[[ûZߌŒôööþâ‹/ÊC´•QBÚJ¦èkßR©4<<ÜÚÚ:..Ný"§DÐI=!VYYäïïïïïÏuÂ*£„´J"‘¨PUUuëÖ-ccãÖ~RZZêçç÷ÁtêÔé»ï¾Sl´¶¶0`ãq GhÙfBZzàÀf}||ÔÜhÊÈÈðññi¶q„ ÉÉÉšÏG´•QBy#t‹‰BÞ•QBy#ÿ›?†¾Éš!IEND®B`‚opengv/doc/addons/images/multi_viewpoint.eps0000664016516101651610000006161413344612246020250 0ustar dimadima%!PS-Adobe-2.0 EPSF-2.0 %%Title: /home/laurent/ldevel/geometric_vision/doc/addons/images/multi_viewpoint.dia %%Creator: Dia v0.97.2 %%CreationDate: Mon Aug 12 16:22:56 2013 %%For: laurent %%Orientation: Portrait %%Magnification: 1.0000 %%BoundingBox: 0 0 949 655 %%BeginSetup %%EndSetup %%EndComments %%BeginProlog [ /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclam /quotedbl /numbersign /dollar /percent /ampersand /quoteright /parenleft /parenright /asterisk /plus /comma /hyphen /period /slash /zero /one /two /three /four /five /six /seven /eight /nine /colon /semicolon /less /equal /greater /question /at /A /B /C /D /E /F /G /H /I /J /K /L /M /N /O /P /Q /R /S /T /U /V /W /X /Y /Z /bracketleft /backslash /bracketright /asciicircum /underscore /quoteleft /a /b /c /d /e /f /g /h /i /j /k /l /m /n /o /p /q /r /s /t /u /v /w /x /y /z /braceleft /bar /braceright /asciitilde /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /.notdef /space /exclamdown /cent /sterling /currency /yen /brokenbar /section /dieresis /copyright /ordfeminine /guillemotleft /logicalnot /hyphen /registered /macron /degree /plusminus /twosuperior /threesuperior /acute /mu /paragraph /periodcentered /cedilla /onesuperior /ordmasculine /guillemotright /onequarter /onehalf /threequarters /questiondown /Agrave /Aacute /Acircumflex /Atilde /Adieresis /Aring /AE /Ccedilla /Egrave /Eacute /Ecircumflex /Edieresis /Igrave /Iacute /Icircumflex /Idieresis /Eth /Ntilde /Ograve /Oacute /Ocircumflex /Otilde /Odieresis /multiply /Oslash /Ugrave /Uacute /Ucircumflex /Udieresis /Yacute /Thorn /germandbls /agrave /aacute /acircumflex /atilde /adieresis /aring /ae /ccedilla /egrave /eacute /ecircumflex /edieresis /igrave /iacute /icircumflex /idieresis /eth /ntilde /ograve /oacute /ocircumflex /otilde /odieresis /divide /oslash /ugrave /uacute /ucircumflex /udieresis /yacute /thorn /ydieresis] /isolatin1encoding exch def /cp {closepath} bind def /c {curveto} bind def /f {fill} bind def /a {arc} bind def /ef {eofill} bind def /ex {exch} bind def /gr {grestore} bind def /gs {gsave} bind def /sa {save} bind def /rs {restore} bind def /l {lineto} bind def /m {moveto} bind def /rm {rmoveto} bind def /n {newpath} bind def /s {stroke} bind def /sh {show} bind def /slc {setlinecap} bind def /slj {setlinejoin} bind def /slw {setlinewidth} bind def /srgb {setrgbcolor} bind def /rot {rotate} bind def /sc {scale} bind def /sd {setdash} bind def /ff {findfont} bind def /sf {setfont} bind def /scf {scalefont} bind def /sw {stringwidth pop} bind def /tr {translate} bind def /ellipsedict 8 dict def ellipsedict /mtrx matrix put /ellipse { ellipsedict begin /endangle exch def /startangle exch def /yrad exch def /xrad exch def /y exch def /x exch def /savematrix mtrx currentmatrix def x y tr xrad yrad sc 0 0 1 startangle endangle arc savematrix setmatrix end } def /mergeprocs { dup length 3 -1 roll dup length dup 5 1 roll 3 -1 roll add array cvx dup 3 -1 roll 0 exch putinterval dup 4 2 roll putinterval } bind def /dpi_x 300 def /dpi_y 300 def /conicto { /to_y exch def /to_x exch def /conic_cntrl_y exch def /conic_cntrl_x exch def currentpoint /p0_y exch def /p0_x exch def /p1_x p0_x conic_cntrl_x p0_x sub 2 3 div mul add def /p1_y p0_y conic_cntrl_y p0_y sub 2 3 div mul add def /p2_x p1_x to_x p0_x sub 1 3 div mul add def /p2_y p1_y to_y p0_y sub 1 3 div mul add def p1_x p1_y p2_x p2_y to_x to_y curveto } bind def /start_ol { gsave 1.1 dpi_x div dup scale} bind def /end_ol { closepath fill grestore } bind def 28.346000 -28.346000 scale -12.775651 -33.300780 translate %%EndProlog 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 26.382103 27.303801 m 35.636231 31.158482 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 39.770325 19.876089 m 35.963602 31.011484 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 39.755819 19.766896 m 26.354375 10.615428 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 19.073007 14.463610 m 25.909747 10.596595 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 19.143717 14.529901 m 30.209910 21.321401 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 39.773497 19.850864 m 30.691755 21.414178 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 26.409218 27.240108 m 30.283685 21.673884 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 26.373863 27.293141 m 20.633135 22.741982 l s 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc n 19.165417 14.588558 m 20.387614 22.321224 l s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 19.100000 14.400000 m 16.382949 18.203872 l s [] 0 sd 0 slj 0 slc n 16.164984 18.509022 m 16.252170 17.956846 l 16.382949 18.203872 l 16.659037 18.247465 l ef n 16.164984 18.509022 m 16.252170 17.956846 l 16.382949 18.203872 l 16.659037 18.247465 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 19.050000 14.488560 m 24.906597 14.480029 l s [] 0 sd 0 slj 0 slc n 25.281597 14.479483 m 24.781961 14.730211 l 24.906597 14.480029 l 24.781233 14.230211 l ef n 25.281597 14.479483 m 24.781961 14.730211 l 24.906597 14.480029 l 24.781233 14.230211 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 19.050000 14.500000 m 19.050000 19.813197 l s [] 0 sd 0 slj 0 slc n 19.050000 20.188197 m 18.800000 19.688197 l 19.050000 19.813197 l 19.300000 19.688197 l ef n 19.050000 20.188197 m 18.800000 19.688197 l 19.050000 19.813197 l 19.300000 19.688197 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 19.092678 14.464645 m 24.218036 11.557188 l s [] 0 sd 0 slj 0 slc n 24.544210 11.372159 m 24.232664 11.836313 l 24.218036 11.557188 l 23.985959 11.401414 l ef n 24.544210 11.372159 m 24.232664 11.836313 l 24.218036 11.557188 l 23.985959 11.401414 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 19.112400 14.473790 m 20.072404 20.419421 l s [] 0 sd 0 slj 0 slc n 20.132179 20.789626 m 19.805675 20.335869 l 20.072404 20.419421 l 20.299283 20.256169 l ef n 20.132179 20.789626 m 19.805675 20.335869 l 20.072404 20.419421 l 20.299283 20.256169 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 19.098100 14.473790 m 23.661770 17.296689 l s [] 0 sd 0 slj 0 slc n 23.980689 17.493959 m 23.423950 17.443545 l 23.661770 17.296689 l 23.686977 17.018319 l ef n 23.980689 17.493959 m 23.423950 17.443545 l 23.661770 17.296689 l 23.686977 17.018319 l cp s 0.000000 0.000000 0.000000 srgb gsave 24.450000 13.900000 translate 0.035278 -0.035278 scale start_ol 3840 3840 moveto 2453 1971 lineto 3904 0 lineto 3164 0 lineto 2053 1509 lineto 936 0 lineto 192 0 lineto 1683 2009 lineto 320 3840 lineto 1063 3840 lineto 2080 2472 lineto 3097 3840 lineto 3840 3840 lineto end_ol grestore gsave 15.605000 17.707500 translate 0.035278 -0.035278 scale start_ol 2217 -381 moveto 1949 -1059 1695 -1265 conicto 1441 -1472 1016 -1472 conicto 512 -1472 lineto 512 -960 lineto 882 -960 lineto 1143 -960 1287 -833 conicto 1431 -706 1606 -233 conicto 1719 55 lineto 192 3840 lineto 834 3840 lineto 2035 837 lineto 3235 3840 lineto 3904 3840 lineto 2217 -381 lineto end_ol grestore gsave 18.150000 20.300000 translate 0.035278 -0.035278 scale start_ol 384 3840 moveto 3392 3840 lineto 3392 3265 lineto 1010 512 lineto 3392 512 lineto 3392 0 lineto 320 0 lineto 320 575 lineto 2680 3328 lineto 384 3328 lineto 384 3840 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 19.101800 14.471520 m 13.346715 16.280384 l s [] 0 sd 0 slj 0 slc n 12.988969 16.392826 m 13.391002 16.004407 l 13.346715 16.280384 l 13.540924 16.481401 l ef n 12.988969 16.392826 m 13.391002 16.004407 l 13.346715 16.280384 l 13.540924 16.481401 l cp s 0.000000 0.000000 0.000000 srgb gsave 18.840000 13.592500 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc n 39.814349 19.733280 m 37.097298 23.537152 l s [] 0 sd 0 slj 0 slc n 36.879333 23.842302 m 36.966519 23.290126 l 37.097298 23.537152 l 37.373386 23.580745 l ef n 36.879333 23.842302 m 36.966519 23.290126 l 37.097298 23.537152 l 37.373386 23.580745 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 39.789349 19.815603 m 35.666246 16.967656 l s [] 0 sd 0 slj 0 slc n 35.357696 16.754532 m 35.911179 16.832997 l 35.666246 16.967656 l 35.627013 17.244397 l ef n 35.357696 16.754532 m 35.911179 16.832997 l 35.666246 16.967656 l 35.627013 17.244397 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 39.803824 19.807070 m 38.001518 25.100672 l s [] 0 sd 0 slj 0 slc n 37.880656 25.455661 m 37.805147 24.901767 l 38.001518 25.100672 l 38.278465 25.062917 l ef n 37.880656 25.455661 m 37.805147 24.901767 l 38.001518 25.100672 l 38.278465 25.062917 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 39.812449 19.807070 m 34.754835 20.719068 l s [] 0 sd 0 slj 0 slc n 34.385787 20.785615 m 34.833486 20.450853 l 34.754835 20.719068 l 34.922216 20.942917 l ef n 34.385787 20.785615 m 34.833486 20.450853 l 34.754835 20.719068 l 34.922216 20.942917 l cp s 0.000000 0.000000 0.000000 srgb gsave 45.164349 19.233280 translate 0.035278 -0.035278 scale start_ol 3840 3840 moveto 2453 1971 lineto 3904 0 lineto 3164 0 lineto 2053 1509 lineto 936 0 lineto 192 0 lineto 1683 2009 lineto 320 3840 lineto 1063 3840 lineto 2080 2472 lineto 3097 3840 lineto 3840 3840 lineto end_ol grestore gsave 36.319349 23.040780 translate 0.035278 -0.035278 scale start_ol 2217 -381 moveto 1949 -1059 1695 -1265 conicto 1441 -1472 1016 -1472 conicto 512 -1472 lineto 512 -960 lineto 882 -960 lineto 1143 -960 1287 -833 conicto 1431 -706 1606 -233 conicto 1719 55 lineto 192 3840 lineto 834 3840 lineto 2035 837 lineto 3235 3840 lineto 3904 3840 lineto 2217 -381 lineto end_ol grestore gsave 38.864349 25.633280 translate 0.035278 -0.035278 scale start_ol 384 3840 moveto 3392 3840 lineto 3392 3265 lineto 1010 512 lineto 3392 512 lineto 3392 0 lineto 320 0 lineto 320 575 lineto 2680 3328 lineto 384 3328 lineto 384 3840 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 39.816149 19.804800 m 43.928429 23.285497 l s [] 0 sd 0 slj 0 slc n 44.214662 23.527768 m 43.671503 23.395561 l 43.928429 23.285497 l 43.994532 23.013917 l ef n 44.214662 23.527768 m 43.671503 23.395561 l 43.928429 23.285497 l 43.994532 23.013917 l cp s 0.000000 0.000000 0.000000 srgb gsave 40.054349 19.125780 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore gsave 40.688754 19.125780 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore gsave 40.993463 19.125780 translate 0.035278 -0.035278 scale start_ol end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc n 26.414349 27.183280 m 23.697298 30.987152 l s [] 0 sd 0 slj 0 slc n 23.479333 31.292302 m 23.566519 30.740126 l 23.697298 30.987152 l 23.973386 31.030745 l ef n 23.479333 31.292302 m 23.566519 30.740126 l 23.697298 30.987152 l 23.973386 31.030745 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 26.364349 27.271840 m 32.220946 27.263309 l s [] 0 sd 0 slj 0 slc n 32.595946 27.262763 m 32.096310 27.513491 l 32.220946 27.263309 l 32.095582 27.013492 l ef n 32.595946 27.262763 m 32.096310 27.513491 l 32.220946 27.263309 l 32.095582 27.013492 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 26.364349 27.283280 m 26.364349 32.596477 l s [] 0 sd 0 slj 0 slc n 26.364349 32.971477 m 26.114349 32.471477 l 26.364349 32.596477 l 26.614349 32.471477 l ef n 26.364349 32.971477 m 26.114349 32.471477 l 26.364349 32.596477 l 26.614349 32.471477 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 26.389349 27.283280 m 22.032410 23.851232 l s [] 0 sd 0 slj 0 slc n 21.737827 23.619183 m 22.285302 23.732193 l 22.032410 23.851232 l 21.975905 24.124969 l ef n 21.737827 23.619183 m 22.285302 23.732193 l 22.032410 23.851232 l 21.975905 24.124969 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 26.403824 27.302920 m 31.342445 29.341766 l s [] 0 sd 0 slj 0 slc n 31.689069 29.484865 m 31.131505 29.525149 l 31.342445 29.341766 l 31.322304 29.062985 l ef n 31.689069 29.484865 m 31.131505 29.525149 l 31.342445 29.341766 l 31.322304 29.062985 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 26.412449 27.257070 m 29.243386 23.167918 l s [] 0 sd 0 slj 0 slc n 29.456839 22.859595 m 29.377784 23.412994 l 29.243386 23.167918 l 28.966687 23.128390 l ef n 29.456839 22.859595 m 29.377784 23.412994 l 29.243386 23.167918 l 28.966687 23.128390 l cp s 0.000000 0.000000 0.000000 srgb gsave 31.764349 26.683280 translate 0.035278 -0.035278 scale start_ol 3840 3840 moveto 2453 1971 lineto 3904 0 lineto 3164 0 lineto 2053 1509 lineto 936 0 lineto 192 0 lineto 1683 2009 lineto 320 3840 lineto 1063 3840 lineto 2080 2472 lineto 3097 3840 lineto 3840 3840 lineto end_ol grestore gsave 22.919349 30.490780 translate 0.035278 -0.035278 scale start_ol 2217 -381 moveto 1949 -1059 1695 -1265 conicto 1441 -1472 1016 -1472 conicto 512 -1472 lineto 512 -960 lineto 882 -960 lineto 1143 -960 1287 -833 conicto 1431 -706 1606 -233 conicto 1719 55 lineto 192 3840 lineto 834 3840 lineto 2035 837 lineto 3235 3840 lineto 3904 3840 lineto 2217 -381 lineto end_ol grestore gsave 25.464349 33.083280 translate 0.035278 -0.035278 scale start_ol 384 3840 moveto 3392 3840 lineto 3392 3265 lineto 1010 512 lineto 3392 512 lineto 3392 0 lineto 320 0 lineto 320 575 lineto 2680 3328 lineto 384 3328 lineto 384 3840 lineto end_ol grestore 0.100000 slw [0.200000] 0 sd [0.200000] 0 sd 0 slc 1.000000 0.000000 0.000000 srgb n 26.416149 27.254800 m 20.661064 29.063665 l s [] 0 sd 0 slj 0 slc n 20.303318 29.176107 m 20.705351 28.787687 l 20.661064 29.063665 l 20.855273 29.264681 l ef n 20.303318 29.176107 m 20.705351 28.787687 l 20.661064 29.063665 l 20.855273 29.264681 l cp s 0.000000 0.000000 0.000000 srgb gsave 26.624900 29.060475 translate 0.035278 -0.035278 scale start_ol 3403 4571 moveto 2755 4571 2247 4052 conicto 1739 3533 1496 2839 conicto 1253 2146 1253 1502 conicto 1253 922 1512 589 conicto 1772 256 2236 256 conicto 2636 256 2987 458 conicto 3338 660 3781 1141 conicto 3954 1032 lineto 3467 414 2992 143 conicto 2517 -128 1912 -128 conicto 1156 -128 740 302 conicto 324 733 324 1508 conicto 324 2783 1285 3791 conicto 2247 4800 3457 4800 conicto 3943 4800 4267 4549 conicto 4591 4298 4591 3915 conicto 4591 3708 4439 3560 conicto 4288 3413 4072 3413 conicto 3651 3413 3651 3828 conicto 3651 3938 3732 4118 conicto 3813 4298 3813 4352 conicto 3813 4571 3403 4571 conicto end_ol grestore gsave 27.259304 29.060475 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore gsave 27.564013 29.060475 translate 0.035278 -0.035278 scale start_ol 1426 4608 moveto 1566 6342 1653 6678 conicto 1880 7220 2258 7264 conicto 2398 7264 2500 7171 conicto 2603 7079 2603 6949 conicto 2603 6678 1653 4608 conicto 1426 4608 lineto end_ol grestore gsave 27.868722 29.060475 translate 0.035278 -0.035278 scale start_ol end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.498039 0.498039 0.498039 srgb n 20.428472 22.579728 0.212500 0.212500 0 360 ellipse f n 20.428472 22.579728 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 20.428472 22.579728 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 30.433515 21.458631 0.212500 0.212500 0 360 ellipse f n 30.433515 21.458631 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 30.433515 21.458631 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd n 26.137854 10.467572 0.212500 0.212500 0 360 ellipse f n 26.137854 10.467572 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 26.137854 10.467572 0.212500 0.212500 0 360 ellipse cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc 0.000000 0.000000 0.000000 srgb n 39.764349 19.833280 m 39.764349 25.146477 l s [] 0 sd 0 slj 0 slc n 39.764349 25.521477 m 39.514349 25.021477 l 39.764349 25.146477 l 40.014349 25.021477 l ef n 39.764349 25.521477 m 39.514349 25.021477 l 39.764349 25.146477 l 40.014349 25.021477 l cp s 0.100000 slw [] 0 sd [] 0 sd 0 slc n 39.764349 19.821840 m 45.620946 19.813309 l s [] 0 sd 0 slj 0 slc n 45.995946 19.812763 m 45.496310 20.063491 l 45.620946 19.813309 l 45.495582 19.563492 l ef n 45.995946 19.812763 m 45.496310 20.063491 l 45.620946 19.813309 l 45.495582 19.563492 l cp s 0.678431 0.678431 0.678431 srgb gsave 25.712692 11.713997 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 26.525192 11.908997 translate 0.035278 -0.035278 scale start_ol 2048 256 moveto 2921 170 lineto 2921 0 lineto 596 0 lineto 596 170 lineto 1472 256 lineto 1472 3701 lineto 609 3392 lineto 609 3565 lineto 1874 4288 lineto 2048 4288 lineto 2048 256 lineto end_ol grestore gsave 30.270189 20.702904 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 31.082689 20.897904 translate 0.035278 -0.035278 scale start_ol 2624 960 moveto 2624 0 lineto 2048 0 lineto 2048 960 lineto 128 960 lineto 128 1376 lineto 2229 4288 lineto 2624 4288 lineto 2624 1408 lineto 3200 1408 lineto 3200 960 lineto 2624 960 lineto 2048 3539 moveto 2032 3539 lineto 488 1408 lineto 2048 1408 lineto 2048 3539 lineto end_ol grestore gsave 21.003889 22.195324 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 21.816389 22.390324 translate 0.035278 -0.035278 scale start_ol 3008 1168 moveto 3008 877 2906 648 conicto 2805 419 2612 260 conicto 2420 102 2139 19 conicto 1858 -64 1499 -64 conicto 1184 -64 888 -26 conicto 593 12 355 71 conicto 320 960 lineto 531 960 lineto 674 363 lineto 732 332 824 300 conicto 917 268 1023 244 conicto 1130 221 1243 206 conicto 1357 192 1453 192 conicto 1749 192 1939 266 conicto 2129 340 2239 474 conicto 2349 608 2390 793 conicto 2432 978 2432 1197 conicto 2432 1448 2362 1614 conicto 2293 1780 2171 1881 conicto 2050 1983 1887 2030 conicto 1725 2077 1539 2086 conicto 1088 2112 lineto 1088 2368 lineto 1541 2397 lineto 1898 2417 2069 2625 conicto 2240 2833 2240 3256 conicto 2240 3468 2196 3626 conicto 2153 3784 2060 3888 conicto 1968 3992 1818 4044 conicto 1669 4096 1455 4096 conicto 1358 4096 1260 4081 conicto 1163 4067 1073 4042 conicto 983 4018 906 3987 conicto 829 3956 772 3924 conicto 660 3392 lineto 448 3392 lineto 448 4215 lineto 559 4244 670 4269 conicto 782 4295 903 4312 conicto 1024 4330 1157 4341 conicto 1291 4352 1447 4352 conicto 2119 4352 2467 4091 conicto 2816 3830 2816 3289 conicto 2816 3086 2762 2910 conicto 2709 2735 2595 2600 conicto 2482 2465 2307 2373 conicto 2133 2281 1894 2246 conicto 2467 2179 2737 1912 conicto 3008 1645 3008 1168 conicto end_ol grestore gsave 35.373302 32.508152 translate 0.035278 -0.035278 scale start_ol 2192 4735 moveto 2307 4814 2445 4885 conicto 2583 4957 2747 5007 conicto 2912 5057 3110 5088 conicto 3309 5120 3549 5120 conicto 4571 5120 5069 4507 conicto 5568 3895 5568 2573 conicto 5568 1966 5435 1468 conicto 5302 970 5025 615 conicto 4749 261 4326 66 conicto 3904 -128 3325 -128 conicto 3043 -128 2772 -93 conicto 2501 -59 2208 15 conicto 2213 -43 2221 -144 conicto 2229 -245 2231 -359 conicto 2234 -473 2237 -581 conicto 2240 -690 2240 -769 conicto 2240 -1856 lineto 2968 -1975 lineto 2968 -2304 lineto 166 -2304 lineto 166 -1975 lineto 704 -1856 lineto 704 4544 lineto 160 4663 lineto 160 4992 lineto 2181 4992 lineto 2192 4735 lineto 4032 2549 moveto 4032 3131 3959 3517 conicto 3887 3904 3762 4130 conicto 3637 4357 3473 4450 conicto 3310 4544 3128 4544 conicto 2863 4544 2637 4485 conicto 2411 4427 2240 4341 conicto 2240 560 lineto 2661 448 3118 448 conicto 3585 448 3808 976 conicto 4032 1504 4032 2549 conicto end_ol grestore gsave 36.185802 32.703152 translate 0.035278 -0.035278 scale start_ol 2880 0 moveto 256 0 lineto 256 490 lineto 587 785 863 1019 conicto 1140 1253 1361 1455 conicto 1582 1658 1747 1843 conicto 1913 2029 2022 2230 conicto 2132 2431 2186 2663 conicto 2240 2896 2240 3188 conicto 2240 3600 2045 3816 conicto 1850 4032 1406 4032 conicto 1307 4032 1209 4017 conicto 1112 4003 1022 3978 conicto 933 3954 855 3923 conicto 778 3892 718 3860 conicto 602 3328 lineto 384 3328 lineto 384 4151 lineto 630 4208 868 4248 conicto 1107 4288 1386 4288 conicto 2099 4288 2457 4000 conicto 2816 3713 2816 3189 conicto 2816 2931 2746 2711 conicto 2677 2491 2548 2288 conicto 2419 2086 2232 1889 conicto 2045 1693 1806 1482 conicto 1567 1272 1281 1035 conicto 996 798 673 512 conicto 2880 512 lineto 2880 0 lineto end_ol grestore 0.100000 slw [] 0 sd [] 0 sd 0 slc 0 slj 0.100000 slw 0 slc 0 slj [] 0 sd 0.498039 0.498039 0.498039 srgb n 35.878808 31.259524 0.212500 0.212500 0 360 ellipse f n 35.878808 31.259524 0.212500 0.212500 0 360 ellipse cp s 0 slc 0 slj [] 0 sd n 35.878808 31.259524 0.212500 0.212500 0 360 ellipse cp s showpage opengv/doc/addons/images/reprojectionError.png0000664016516101651610000004621413344612246020523 0ustar dimadima‰PNG  IHDRi袂‚ÐbKGDÿÿÿ ½§“ IDATxœìg\WÆŸ™í…ÎbC½E±w¬ÑX¢Æ^P±$kì{A£bb,ˆ½k|íbWì{oˆt–Ûw羑²KÛEçÿóÃpçιgöáÎ=÷žCB`z½~×®]R©´G&>ÂÂÂò¥Â5¥“Q5-Z”\Ø>±°°X?¹hGºj¼zõ €¯¯¯T*-ÇXXX¬*»w–Lª@&“½}û–Õd9ïø\5Œüú믬p°°°ùdÞ¡V«×¯_¿bÅŠÐÐÐLýÜÝÝß¼y# ‹Ö=+%M;t:ÝÎ;—,Y’i®‘NÉ’%ÝÜÜŠÖ7–"‚òêÕ+Ðô¢Õ«Çy{[Ú–âAšvœ={vܸqÏž=³´?,¢ýw3f5zp÷D—Î(_ÞÒÞ°>¾³0 sàÀ !‰]ü`I‡ÕŽ/Ÿ7oÞxyy½{÷®U«VgΜ±··Ï¡³ˆ¢ÚÖ¨~£w¢×߬Væuí²I©àQ”_Jê±ñlð…Å«_8¯^½òòòzÿþ}ëÖ­;fÊIh©øÄÄ_u"Ñ«  ¨nÝ Ñ ë×礃=MRªšDËà †"ðœÅÊaµãKæñãÇÍ›7 m×®ÝÑ£G%‰)OÕãó+”*yqè0r-.•+ãþý6 Üv“Uârhu¢äwµlðåk‡ÕŽ/–‡¶iÓ&::ºk×®G‹Å9t6ÆYÒ( “HÎþ‹ÕÃjÇ—Æõë×;t蘘8hР½{÷òx¼¼Ùñ‘ˆuAàÄ_\Ÿ3ǰe lm±s'v呂yv¶»…µ!UÑ9&.™aƒ/_¬v|Qœ?¾]»vIIIC† Ù¼y3'i8Z ¹ÜÀî=øU«%?9}+WÀÏ?#$@±èœ‹³Œ¦ÕêæÑò÷z6øòuÁjÇ—ÃÙ³g»té¢P(Fá@C¥b†Ã¹;c&€[ h{õBïÞHJ A04ð¯»É*ó¸uºFÑòÿØàË׫_Gíܹ³R©7nÜ_ýeŒ›ä“¡1¢Z¶rjÒD%—ß_¹ÿ%”6*p¹×\e­„‚Hƒ¡e´ü0|ùj`µãKàÿûß?þ¨Ñh&L˜°jÕª<G¦­7§£P "çÌp÷÷ß•¶nEaöl}´ZíìÙ³W®\Y 3Žt|¤jÖ*×¥‹.5õÎ’%h׿üýûC¥2vãSÔ'_{[LOLŸ¨c·®é°ÚQ¼Ù±cGïÞ½µZíܹs.\Xàö;‰„îÎK½^0o>Åá<^·.éÍ,_Žš5ñô)fÎLïIÓlmö8;Š(jcª¢³<.‰aÎ}ɰÚQŒÙºuë!C ƒ¯¯ï¼yó c.à-ØU֣ʠA­öæÜ¹ ±u+ø|¬^“'3öï%wqváЧ՚fѱ!lðåË…ÕŽâJ@@À°aà Ãï¿ÿ>mÚ´Âh¸TL{•ªj pE¢—»wËïÝC:˜?„`øpÄÅeìßHÀ¿î*«Êã>ÖéEËokµ…ç‹aµ£X²fÍšáÇBÖ®];yòäB«<—ÛJ(PrÄÁ±æèÑ„a®ÏšS§ÂË 1âóG®ºÊZ QC‹èØ=JU¡zÈbXí(~¬ZµjüøñE­[·îçŸ.‚}$b›R•õgÍ88„œ<vþgG1E¤*;ÉãÙàË—«ņéÓ§Ï›7Çãíܹ³_¿~E<ú©Àv…R+ÖŸ=Àµ™3½þùeÊàêUøúfùlO±è¼«³+‡>«Ö4–³Á—/V;ŠS§N]¶l™@ ø÷ß{÷î]ôÔâñ<ù¼D†9¤TU>ܱjÕÄ—/Ÿ€½=¶oMcÞ­Ç„ hÓr9rÛ{Ò],ºæ*+Åá\ÕhGÉ_èØ´§Å V;¬Nׯ_¿½{÷:99?¾I“&–öè†H$6¥*8תU±o_ƒZ}3ý$McëV8:âÈlس©Ú|Þ 7Y]>ïµ^ß$Z~I£)\×Y V;¬ µZݽ{÷8;;Ÿ9sÆÓÓÓÒeÆ["æQÔq•:Â`ÐxñbŽ@ð|Û¶ø'OÒz”,‰`Ò$¼|™³µ’Î%WYg‘0ža:ÄÄmgƒ/ÅV;¬•JÕ½{÷ãÇ—(QâòåËuêÔ±´GYàÊ¡;‹„z`«B ÀÖãÆÈ‘Ä`¸–!—zôÀ AP(п?t¹$1•RÔÿdNcm¤B¼ã¦'&³k§ÅV;¬…ÔÔÔŽ;ž:uÊÝÝýüùóU«Vµ´GÙb<矪4~ÉëÿößÖ6øÈ‘ˆ+W>vZ³øï?,^œ«Aàç`·ÞÑž,KNé¯bƒ/V«VAJJJ§N.]ºTªT© .T©RÅÒåDG‘° —óV¯¿¤ÖÉdßNœã¹tìì°c8,^Œë×M1;R*9êâdKSû”ª61±16øbÕ°Úay’““;vìT¾|ù   J•*½&ÆhÐ’‰mú°ï­^ß$Z~AÍ_¬V;,IlllÛ¶mÿûï¿jÕª•)SÆÒ™Š—ÓZ(P²K‘–¬æO?ÙU¨ðüù‹;>öãñ°u+ÄblÚ„ýûM4îÎá\r•u æ;yÜV6øb•°Úa1äryÛ¶mïÝ»W£FóçÏ»¹¹YÚ#óH+¿ª0þHóx,pcöl½*C’ÁªU±lŒÈHK(ê Ìiš­–!q ã’ØÅkƒÕËÑ¢E‹ÔªUëܹs®®®–öÈlzˆ„2š~¨Ó¥—’¬Ô¯Ÿ¬nÝÔððGk×~ÒuÌ|ÿ=bc1dL p_{Û Žö<ŠòKIíÃ_¬ V;,@xxxëÖ­Ÿ?^¿~ý‹/º¸¸XÚ£¼À§¨þiyLÓ¦ ¨&K–¸½x±&!ácWŠB@\]qú4þþÛ¬QFH%ÇdNv4}@©jÍ_¬V;ŠšàààfÍš½xñ¢aƧOŸvpp°´Gyg¸T `—R¥ü0#(Ó¡Cé6m4 wÿøã“®..X¿¦LÁ£GfÒ^(¸âê\–˹¡Ñ6ŽŽyÊ_¬V;Š”7oÞ´jÕêÝ»wMš4 ´···´Gi˜£M§×ÏOb˜ª(4^ºuåÊÔ°°Ozwë¨Õðö†™E[jðx7\eõùü`½¡QtÌI¶b¶ÀjGÑñêÕ+//¯÷ïß·nÝúôéÓvvv–ö¨ð‘¦•_Hoq­_ÿ›ž=õ*ÕíE‹2÷^½•*áÞ=Ìkî@nÎeWç¾bQ CºÊãþIQb±¬vOž €­ eÆÒM æÎåI$¯Œúü0Ëo¿¡Q#„…aüø<Ž(Ÿ9ÙÓô¿J•WtlTVuaX V; —›7o¶k×.!!¡G{÷îåóù–ö¨ài"àWçñ¢ ̱ K˜’%jB>9 g„ËÅŽ°±ÁöíØ³'oƒ¶ ®¸:{p9·´ÚzQò{Ú\Nú³8¬v"ׯ_ïСCbbâÀ÷íÛgÍ‘·8K:äŸ3â9uªÐÉ)üòåS§2?P¡ŒAÜŸFz¾B3©ÎãÝqsi.à‡ -¢åÇÙàKÑÂjGaqáÂ…víÚ%%%y{{oÙ²…ÃáXÚ£BÄ["PÔI•:4Ãëßήތ®M›F>Ïfk–áóTÆ2¶lEaæLÜ¥K•J5a„իW×¾Ú …e¹œ`½áü§7ª ì\»vò»w³L›Þ¡F‚Fƒþý‘ñô­ù ‘ˆÏ»8;Óô)µºY´<” ¾2¬v$ÆBÓZ­vÖ¬Y+W®üz„ ÍP~!Ц-\àöÂ…Ú䬊H®XÊ•ñô)fÏΧMüën²Ê<îC®Q”ü?6øR˜°ÚQ`ìØ±Ã(sçÎ]ôùv쯩˜ü«RgªóV®K—’­Z©äò{þ™Åcb1víŸU«pî\>}ø†Ë½æ*k)D ­¢åGÙàK¡ÁjGÁ°mÛ¶!C† __ßyé…ŽŠùŒÑ)Åá´ µ„ìü,ÓW__PÔ½+”YÖš¬[¿ý†·7ŒÕmó#Mº8 ”ˆS é.[’šOƒ,YÂjG°yóæaÆ †åË—O˾ ü×€qÅÔ?5³v¸5lX¾kW]jêìJ.Ìœ‰–-žk1JSPÔ6'‡¹v6 0!!iT|"{n¿Àaµ#¿üõ×_>>> Ãüý÷ßS¦L±´;¦«Hè¡ët·>;eßdÙ2šË}´n]Ò›7Y&6™ ¾(¬vä‹Õ«W7Ž¢¨þùgôèÑ–vÇòð)j$ó©|#•+W4ˆÑén|~@ÎH¹ri=ÆŽÅ»wâOo±è¼‹³Œ¦O«5Í¢åïõlð¥À`µ#ïüùçŸ'N¤(jýúõ£F²´;Ö‰„v)”Ÿo²h´p!W,~¹{·üîݬ:½{#) ¢€‚¬üën²*<î#®Q´üŽ™i‡X²ƒÕŽ<²`Á‚_ý•Ãálß¾}øðá–vÇŠ¨Ìã6ðS ٯ̼_CZ²d­Ñ£AÈ'Åk3±nJ—ÆÕ«X¾¼ \ªÀå^s•y ‘C«èØÿ±Á—‚€Õ޼0}úô¹sçr¹Ü;vôïßßÒîXÆò ›Yœ.©7s¦ÐÑñ}``hváXlڊœ9¸u« \r éS2'o‰XAHyܼ¤¬vš°˜«f3mÚ´eË–ñx¼Ý»w÷éÓÇÒî £M§·XdKS×4ÚÏó êN™cñÚì†k×cÇB¯‡·7”V؉OQ[œV9ØQÀü¤”ñ‰:6oP>`µÃ !“'O^¾|¹P(¶¿y“–á¨~ýÇò°Ú‘ FáØµk—­­íÉ“'›7oniŠ ƒ$b!EV«C²Ú‘U¡gO·Æ‘‘V¯ÎÖMcÛ688àðaøû¸‡64uDæô³T¢&d@l|þƒ/r9&M€ 0bÄ'·ÒCF¬v|ètºþýûïÙ³ÇÑÑñüùóM›6µ´GÅ Gšî.2ÀælfM|}ü·|¹:‡óo¥Ja͘0/_¸“\`­£}zðeX\B~‚/K—¦Õ˜6 ™0ܾvÁjÇ—F£éÑ£ÇþýûÏž=ëééii ‘‚Ѧ“¶Ñ#U™åÑ’-Z”íØQ›”tgÉ’œ¬ €~ý P`Àè %%Çxé~gG1EmV(;Êãó|Q*±y3¸¸à‡2ß5Î;x<|ûm>µXíȵZݽ{÷cÇŽÉd²³gÏÖ©SÇÒKZ ¸Ü0ƒá¬:ë­œM—-£húáÚµ)9gKÿç”)ƒ;w³ÊäƒbÑWg7çœZS?JþRoöÉÛsç˜]»"SžÉäd<~ 5k"»ú<›6¡re´jeî°¹“7ËèÝ…Le…„†bÖ,V;²B¥RuëÖíäÉ“îîî—/_®]»¶¥=*®PÀìWL8Õ¬Y©ƒZ}3ç µvvر-Â…á*€|þ7Y>ïµ^ß$J~ùó«9råJÚE£F™o;£åðÂâãSX¯3y³Ü¡ÎúVéÒX¼˜ÕŽÏHIIùî»ïNŸ>]²dÉ .T©RÅÒo†JÅà°JcÈúE ÑÂ…àù¶m±9§;nÞ'B¯Ç€HI)_’ÎeWÙ÷"aô‰ÛñY£HO-ðù¯ÌÁƒi™¾Ã*ŽË£«‡ÕŽOHNNîÔ©ÓåË—Ë•+wåÊ•J•*YÚ£bOIç;‘PKÈöl¾‡¶5F" sã·ßr±µhj×ÆÛ·øõׂwôRŠ:,súÅF¢!dp\¼¤dâãÓ.>iø‡§]gÒŽ?ÿÄÿþ÷IK᥸-pˬv|$>>¾M›6W®\©P¡ÂÅ‹=<<,íÑ‚D `£B‘Ý—°þo¿ñmmƒ ¿x1'Cví‚H„‘Ã~ö|ÃÖ8دr°£ùI)ýbãÕ&¬"s¹i™Nùãß ±Õ«lß°+WâôitîŒãÇÓ ̘‘¶“½G´¥áC‡P±"ºvÅ®]hÖ ÆD1qq4]º CôìùqUbÃxy¡W/xzâï¿?—¥e 6 Í›£{w4oŽ-[²ý€ññ:žžèÙýú±{Ò?[·n]+V|ÿþ½¥Ý)j|||øûû†q!%Â"v5ûí›7çÏ÷ö5lH²ÚÃþ +W€8;“ÈÈvô3NªT6¡á kc0äÜyøð´]ç|lüãÒ½;©Y“¤Y³ÌxzŸ?@êÕ#qq„ræ ÈÞ½o•+GŽ#qã!¤Q#2thÚÝNˆ—!„¼|IhšÈå„O|}s·Üµ+éÚ•?ܳgD($;v¤Ý:z”$44íÇï¿'Í›µ:íGvÞr¹¼mÛ¶wïÞ­^½úåË—K—.miŠšBŠÑáƒ+¦Ùo!­3i’ØÍ-êæÍ·GŽäbnüxtìˆØX ’íIÜâ;¡ðŠ«¬4‡sM£m%ñÙ±àŒ´m›váç­:/Æ’%˜?Ož¦íìHàè˜fÍÆæ“ôieÊàûïQ«–.ųg¸q½{úÒ%h4ËÁ00fVrpøä a––ƒƒqä†M U©‚öí‘åf½W¯pü8ÆŽý'bµ-[¶¼ÿ~Íš5ÏŸ?ïææfi¾@†IŰW¡Ê.i(O*­?{6€kÓ¦19ÇG) þþprB` þù§0¼ÍH-¬.Ÿ÷F¯o-¿¨Î6øÒ£jԀ˗!“A&Ã’%Ø·‘‘yÜNÓYê‹ñú5üù'úöEß¾8u U«B¥BýúhÛ: Y3øû#»ÿé–»íÜÝ?ÞòðÀ«WY<òü9T¬˜ÁˆyŸæ‹#<<¼uëÖÏž=«W¯Þ¥K—\\\,íÑ—I%.·¹@  doöù8jŒi÷Í7 /^<ß¶-sîîØ¸¦LIû¥.LÜ9œK®²."a<ÃtÇmËfÑ—ÇC` zô€DmÚàöm´ió1¦\€!Xãÿ9s°göìA` ?†½=x<œ>³gQ¥ ~ùÝ»›d-ãìa²^U5.âdÜœòUkGpppóæÍ_¼xѰaÃ3gÎ8dZg)PŒå²Ûè€æñ-Xàæœ9ú\SþtïŽÁƒ¡TbÀ€Ì‹“…€”¢ÉœÆÙHµ„ ‰K˜ž˜œeÀÙÝ"5II8xÕªÀõëàà€o¾)0Ê•ö*”‘øx¨ThÓþþذÇŽåÎ6.âFD|ly÷•+gÑÓ9xöìcË׫oÞ¼ñòò nܸq`` ½½½¥=úÂé%9ÐôM­öAö¥+õíëâé™þpíÚÜ-®Yܽ‹ùó ÒÑlà«ìÖˆà“ IDAT;Ús€eÉ)}cãU¦­¶Ü¹õêeqK*Ehh^œ©XÍ›Ã×7íå€qãîݻش)­E"L©4';åÊ¡[7¤½Â<{†3g0aB=ëÖE­ZX²$­öVjê×gyõê•qAÔËË+55ÕÒîXcºæ7ê(?Ç% $l||b}Bý€õ*cT g®\!¡iR„IUN©T¶¡á k­Ï%øœ|™93‹»ûö;;R­Y¾œœ8AªU#¥J‘-[!déRÂç//òðáÇ[¾¾D¡H{öý{Ò­qp ¤E ²v-!„ßÒ} ”ˆÄuN­y“ã&ŽF‹Ñ<ÞÓ€€øŒ+ûÙQ¥JZ!¨Ÿ~BÎgù  Eý+sškg£~ŽOŸôyð%½Þ;èÙ÷ï™w…Î×¢7nÜhß¾}BBÂÀYá° v4ÝC,"À–¨ÚW¬X}øpb0ä~@ÎÈèÑè܉‰ðñÉzCUá@smm»nñä\¿”ÔÞ±ñÊOßûââ@ÈÇ;™k…ÎW¡/^lÛ¶mRR’··÷–-[8Ž¥=úª1ÛœM2±tΛǷ±ysð`”qƒDÎP6m‚«+Ξ…Ÿ_Á8jS¦àÈb¾û ;†>¨TµŽŽÎ&ÛÀÆ—¯çÎëܹ³B¡:th@@+§¥PP‘Ë 7Nå¸b*rq©=nŒäLÁÅë×Àôéxø°5yó°b„BüE]-éìÁåÜÔjGÇ<)œÜˆVÅ®gΜéÚµ«B¡øå—_6mÚDÓ_øçÍ3EgI fÜcš[fºÓ¦‰\\Â/_9yÒ$Óݺaøph4èßÙd9,@V®Äüùàr±gZ·Fuﺫ¬Ÿ¬74Ž–ÿÒ+fÉߥ#GŽtéÒE©TŽ?ÞÏÏ*¼´*,f2D"æQÔQ¥*ÒÓ‹ ߯¦Þôé®N›FL\ÅXµ •*áɘ¸P’WöïÇ”) (üý7ºuKktãp.¹:÷‹RÒM÷wJNá¤âΫ‡êÕ«—F£™9sæªU«Xá°*Ü8œNBخȥ¢RÍ1cìÊ—{ôèå®]&™–H°s'x<üù'Ο/_³bÏôïƒK–`äÈOn )j§³ã\;ðKBÖÁ—/ƒ/S;8ЧO­V;gΜŋ[Ú–,øP~!ÛdbF8|~ƒ¹sÜøí7ƒ‰É‡ëÕÃÌ™` ü1`Á±v-ú÷‡^?ÿD–K10ÏÎv“£¢üRRü,øò…`é­y$‡C([·n5.ˆú¦gMbÉ‘#GX¿~}‘¨#Ä=,!a—ÒQec0ìþö[?àþªU&[בF@zö̯£Ÿ²f áp@Lùå:«RÛ‡F $¬vdt¨¾€+f[œâ:ï˜4iÉJË·lÙ2lØ0ƒÁ°lÙ²i³&±XÜÜÊ/¤CÑ´±xííE‹´É¦•}är±s'llpð vîÌ·³@fÏÆØ±0°|9Lùåj#Üv“Uârhu¢äw³?@\,±´xå…ØØXwûöíLíýõEQE­X±Â"Ž_Š~ÞAy«ÓÓ!a¢÷á ¹¥%„üëååܘ3ÇŒ6l ±³#ïÞåÝKB! ññ!ár‰¹I]c †Qr„„I߇Uªòé‰õP,ç‡Öét‡Ó×üüüÆŽKQÔÚµk' ³˜LQÆhÓ)Çå´ T„˜Rƒ¾‰¯/(êÞŠʨ(S1?þˆ¤$ ˆ:9//lÚ©GŽÀÇǼÇhú´‹Ó@‰8•äqkRRóì‰UQ,µc÷îÝ:”Þ²råÊ &PµnݺŸ~úÉr®±˜‡OÚkKî±L× Êwë¦S(n/ZdÆÿü77\¹‚?þÈ›‡×®¡^=\»†råpåJ7• (j›“Ã\;—4*>Ñ슕Vˆ¥'>f–¾ÅëéÓ§„ àr¹;wî´´wÅ•Q£FX·n]«bÇЄ„ÝÕhsíÿüù_\î_<^â«WfŒqê¡(Âã‘[·ÌòaˆŸ@Z¶L+\Oö(”Â÷á ë›dÈ­š„uSüæd>l:|øðôéÓçÌ™Ãår·oßÞ¿ËúÆb.BŠ ȾüB:•+Wñöft:SÈéÐ?ÿ ÞÞPåþrd$6ݺaÜ8hµ;gÎÀÙÙŒ1³£XtÎÅYFÓjuóhù{}Þߤ,¥ÅËlêgÈ6mLÿÅãñöíÛgi¿Š7–šwBjµ ³ PäZÕ‰Ôððµb±EEß¹cÆ ©R…ie‘rãøq"“€¸»“sçÌÇD^ët•#¢V",òŽ .뤘Í;‚ƒƒï¤gS¢¢¢hšöõõíÕ«—½bÉ5y¼ú|~ÃükŠ©ÄݽÖ/¿€k3f˜1†XŒ;ÁçcÍœ8‘CG­ãÇ£sgÈåèÔ ÷ï£uk3Æ1‘ \î5WY+¡ Ò`h-?\1Û¬PêLØŸÆ Ì™àúŒ³ŠÂ•+—–UlÜ8cÙÕP¯¶oOK–¼k—š÷‹Î»8»pèÓjM³èØâ|±ôÄÇT†)_¾|Fϸÿ~¶8Sþ±ì;‹‘ªQ ;lÚ®mF¯ßQ­šðÐXÔÈ,úô!iÒdÕŸ¡¤zuòä‰Ùf –7:ñ¿€[Xä-ÆÂÞ˜@±™wܺuëíÛ·J—.=f̘3gÎDGGoß¾ýÇ”k³s†šP~!ŠÃi´h€›óæis®¹ú9ëÖ¡téñ×úL˜D«ÕèÙW®¤Õ޵ å¹Ü«®²ÖBA”ÁÐ":v Q'˵´¦rýúõÉ“'÷éÓÇÓÓ“MäóEâ-ÏJJ>¡RG î&¤•­Ð½{‰&M"¯]{°zuýÙ³ÍÉÞ]Û/ó'×OŽó»Gž}ÎJBÞé !z}„1€`1E9Ðô;Ûrå&…¢lüs;›yv¶Eì›éí˜e]–/ÝU$<¨TmQ(gÚš´êÐÄ×÷`‹w—/¯1r¤ÈÅÅŒÁÚ¶m3þøÛUå]I1ç^a/rÄ1ÌeµæžN÷ŸVwW«‹Êñ`pçp" †ùI)¡Ã:{žUþ±,6ÚÁR¨XäíçøHÄ•*ÿTÅ [S¾.îÍ›{têôîĉ;¾¾ÍÿüÓ¼Á|}]ÏŸÇǘ2ëÖåÉßœ`€«í)•úŒZóŸV›1|§¨RNY.§ ‡#ø  JB&ToxªÓE|—€Tå+þˆÌÉÞúÒt³ÚÁbEt Ëp9ÁzÃEµÆK(0å‘&¾¾!§N=úûïZ¿üb÷éjz.ص õêaýz|ÿ=ºtÉ£ÓŸb.ª5•ªC*uúüBHQÍüÆ~M¯÷ ›Ã+™šûZÝ6…r«R©dHFësÖEV.§‡,€Õ‰Ë× žLÌ´=¦œjÖ¬<`€A«½5¾ÙãU¯Ž ÀǦ§Ɇ7zýoIÉáQmcbÿIUD 5x¼i¶6§\œâJ•8ãâ¼Àζ—XT9Gá ¤¨FþZGû7%\[ ‚õ†œKpZV;X¬‹¡ TªâMÞ%ÕháBŽ@ðbÇyʽþú+Z·†\Ž¡C‘§W6ªÕmbb+FD/JJ 3*r¹ ílŸ—p}TÂÅ×Þ¶ƒP(ÎÓ‚…‡sÆÅ¹¹O€³jÓò<!¬v°X\N¡@MÈ®ÜÊ/¤cS¶lÍŸ& sìh‹šÆ¶mptÄ©SieåLFGÈv…òÛȘïbâΫ5"Šò–ˆ/¹:¿pwmgS™W \àO{;˜º.JXí`±:Œ{L7šóm©7kßÖöÝñãa.˜=^É’X³~ý/^˜ò„Ø¢PV‰Œ—ðP§sçpÛÛ¾/é¶ÅÉ¡…@P°A‘z|¾Œ¦c&"i V;X¬Žî"¡Œ¦êtwLÞo.rv®;y2ŒÅkóðêÑ¿?ú÷‡R‰þý‘ã  °U¡¬=4.á­^_•ÇÝæäìî:ÓÖÆ©ÐB!n€X+;êÂj `51Z#|ŠhZù…Œ|;i’ØÍ-úÖ­·Ÿ&Á6•µkQ¶,îÞÅÂ…Ùu T«ëFÅ ‰Kx­×׿óö9;>.á:H"æòþ‹D†`OY×·Õº¼aa1bÌè±K©4½¢O"iðÛo®MŸÎä!*ag‡íÛÁá`É\º”éæc®mLìw1q´º \î^gÇ{n.½Ä¢"øþÄ2L˜Á ¢(WŽu}[­Ë#Õy¼F~2Cö›s¬£úˆö+&¼xñ|ëÖ¼ŒÚ¼9&MÃ`èP|("•ÌI Iu"cΩ5Î4½ÊÁîi —ÞbQ‘íô<¯Ö ©€/°²Ý¥¬v°X)¦—_H‡æñŒänÌ™£Ï[—… ñí·Æ„ N©ÕU"£W¦¤2À(©ä¹»ëxia¿¡db›B à{‘°(5V;X¬”¾± Mi´Ïtf¼€TìÝÛÅÓSñð¯¿ò2ª@€;!%ï?0âÎÝN1q‘CC>ÿ¦›l£}á­†fÇ{½á”J-ø°dU°ÚÁb¥H)ª·X`³ å>BQM|}ÜYºTŸ—«U;ç¿©Öé3þ.®`£ýu7Y=>?/¦òÍ¢äð£Xäl}çY¬Î!–t|$[MK&–Né¶mK·k§IL¼»|¹¹#*ŸØ®Y‹’¥šÝ¾õ`ÆÔQ±¥–žëô›S\à7ÓN1¬v°V£M§±€_Ç‹10GͬBÐì÷ß)š¾¿zujh¨éO]TkjEƬMUð)j9M]úyTù]»Ò¶9“¨†I%²EµÀaµƒÅª1«üB:εkÓ«—A­¾e<ê–X””Ò&&ö­^_‡Ï»ã&›RÊ6nQŸ:9fØ.$¶)”çÕM/±·Òô?¬v°X5ƒ%bER©Í-¿ØdéRŸÿtóæø§Osî™Ä0Ýäq¿%%`¦­ÍMWY ºwÇ!Ðh0xpΛM œ`½a|B€vE¿@k"Vê ‹'šî&w‚›õ m¹rÕ†'CÎäétõ£äGUj{š>,sZloûI’®5kP±"î߇Ypó‡ŽþqñI ÓM$´ÂðJ:¬v°X;Æ£q …¹Ç9ÎË·±ysèPäµkYvØ­T5Ž’¿Òëkòx·Üd]>ßC!•bËp8øãœ?ŸçóÀ¤Ä¤m)g““ƒuíûV;X¬¶B—óNo8gf ‘‹Kí `< ÷)˜ž˜Ü?6^AH?±èº›¬"7›õÈ&M0}:ÞÞÈ[Ð×üS¥(„µÏÙÑjßVŒXµs,E†uÆYŒÐf–_ȈçÔ©"—ˆ  wǧ7ꟸ„eÉ)<ŠZå`·ËÙQ’óVÑyóа!ÂÂ0v¬ùî›ÁµfLB€uŽö–ÙQb:¬v°†IÅàJ-7ó:O*­7c€k3f† "äGyÜf…RJQÇeNãm¤¹[ár±c¤RìÚ…lŠ柛Zm·Ø8-!m¤ÞV¼Ì‘«_#þþþÿûßÿržeètºM›6ÏðçÚ‚”âpÚ‹„ZBvš¹b  æèÑvåËÇ=zôbçÎX†i{X¥.Éá\w“µ3-2|ó Œ;Í~þ!!æú+w´Úö1±) ñ‘ŠW8ظý€Վ¯‘öíÛ÷éÓ§nݺY*ˆN§ó÷÷¯T©Ò¼yóÚ´ic?ÇÇüŒF8|~ƒyó\ùí7¯ÐðÛZmE.7(=k:?ý„Α”„AƒP )¼žêôcâ’Ò[,ZïhÕë£aµãk¤L™2C† ¹ÿ~÷îÝëÕ«wôèQc;Ã0[¶l©R¥Êˆ#Þ½{7}út¡ÐZŽov ]8ôcî†Æì­• °ûö[UHˆs@@5÷¼«s^êPàꊠ ˜[ &{Þë å±± ã%lqr°®2 9cÉb¸,–#88˜—ᯋ‹ ™L–ÞRªT)µZmi7?arB"B†Ç%˜û`„^ßfûN?àwGǨøø|9qø0ˆ@@îÝË—B!¯uºo£Ö02&ÙÀäß`QÂÎ;¾R<<<† ’þcLL ¹\žÞ2}útÀäå€"a¸DB{ÊÆŒxP<Ãtˆ‰;×¢eD³f‚øøà|NºvňÐh0`Tù*7}G«m-­××ãóO¸8ÙÐÅåe% ŠXeXŽ¥x÷î]¥J•t:Ýç·J•*õúõkkÓÍ£åW4ZGã9—\I`˜Vѱuºê<Þ¿!o›4á‰Åƒ_¿»¹åÝ …uëâåKL˜€•+ófc¿R5(.ACH/±h»“ƒµå3vÞñõâáá1bĈ,oÍž=Û …ö˜n2-£‡‚ïåquºr\Îi§JUèÞ]§PÜÊ>›±IH$ص <V¯ÆÉ“y0ðOª¢_l¼†Ÿ¤’ÝÎŽÅQ8v½ãëæýû÷ŸkD¹rå´Z­¥]ËšT†± GHØc<0YhÄs­ÎØ’ðâÅ_\î_<^ÂË—ùueÞ<wwkÖs‹’’©0„„MIH,f+ŸÂÎ;¾jJ—.íãã“©qÚ´iŸÿ-ŸÇ0‡³I&i0 Œ7 ím»~v4Vâî^{ìX’—âµ™(_>m£Çرxý:‡Ž§ÕϨ˜ÛZm9.窫ì €]ï`!äÝ»w|>@É’%U*•¥ÝÉÕÉ) k-ÿüCH»h9BÂZGË Ù<®NHØàää¼?}º¼éÕ‹¤iS¢×géÏÂÄdNHBÂ:ÇÄÆ²sªøÁÎ;XP¶lYã^«ÚHš%b!EUkB>K&¶)UqF­q¢émNÙýr ìí=§MpeÊ’ÿ"¯k×¢D \½ _ßLw¢ LWyÜoIÉ–ÚÛ‘99X÷±zó°´x±XU«VµÚðÊçôGHØÜĤŒÑzƒchBÂv+”9?®W©J—ö^ìÞ]ÞŠ"\.¹q#½mBé0·°È *ëÚ¡[ |A*È’J”(qâÄ +_éÈHúѸŒIIñ ÓA(ì+åü8G(l8w.€ë3gòŸ‹´}{Œ ½"55ÆÀüß76>–aÚ ÿ¹ÉZ™~`·øÀjK–vÁ ¼„‚o¸Ü0ƒáŒ:mÅô¹N¿5UÉÖ8št†½ê!ŽÕ«'?õ÷/‡þø5jàõëý›kDFTªlhj£} ‹³;§8p3V;XŠ%0DúÉ©|c µ¡RI¶Ù3Yàp/ZàæüùÚ””ü:$Êwìè½nCïzȦPðÈÍu”TR¬wpä «,ʼn˜ Q©c L<ÃTª8ÀLsJ¨•ÿá‡M›ªbb¬Z•O ÀÆTEMg—ý;Iе¾KÎCÙ<ó/V°ÚÁR\qãp:Š„ZB¶)”»*5!DB3¿±Æâµÿ-_®ŒŽÎ›ÕšzQ1#㣠Œ—€ÿpîo?ÿ³–92oÖŠ¬v°cŒGãüŠ“j5€¹-‘~Ž{³f;ëRSï,]jî³oôúž±ñ^1±÷µ:.gŸ³ãyWY¹åË`k‹#G°aƒ¹‹ìžt–bŒ(a0H(JAHxI·<,LÆ=~¼ûÛoigÀ³gvåË›ôÃ,ONY¢Ð"¥¨v6“l¤Âô òÛ¶ÁÛ þû•+›ëOqw°c¸À`‰€‚'šÎ[DéF*´Ú[óæåÚ9–af$&{„G-ONÕ2T"~éî:ÓÖF˜ñdÍàÁèÛ  @VéQ¾ ØyKñæ­^ÿMD4<8Üà’®y3’²½reF§ës玬N,ûD ~)Š¿RSYË:Š„ íl=ùÙìˆILDíÚxÿsæ`þü¼yeå°ó–âMy.·‰@ ‚Ñçy{¹MÙ²5G& “å¹ZÝиˆè¥É)) é(Þt“9 _½3fL•*UÄb±««k«V­¦N* /Ü»‡M›@ÓX²ׯçãóY1–ÞØÊÂ’_¶¥*†° µ&ÏF”rù:;;? ôÜ9c‹‚a¶¦*ZFÉÆyïÃûÉãni4„†a/^Ìårišîß¿@@À¦M›š6mjüNÑ4œœL!'€”/OŒ?§N‘Nˆ³3¡i",¬>ƒÕ–b’a„ïÃV3"ZÍä=×­E‹ü€Ý HU Œ7&(CH˜mhø´„¤Ð Çd'Mš@(ž:u*½155•¦iU«VMkR«I­Z >>yö*'–/'‡C åÊOÏB(+Xí`ùðŽç„„#$¬CtldVgás%JoØ&ýÝÝݨ½~£Q5šDÅø§(2U?ؼy³q~±~ýúŒí<0¶<øcëãÇD($Ù·/OŸ,{?&4¦?ýD!{÷²ÚÁÂb Ã]­ÖxˆÖ&4|L|ÂMF“ãDÉ0×Õš¿’S}â⿌6æm¶x©°°|…EqñéYN3ãàà Aƒ̧ö7nÜhÔŽ5kÖ|òÌ€8;“ˆˆ‚ø¬˜<9M8Ò…)1‘x rV‰H—.]š`Ú´iÔ§oß¾m¼¨_¿þ'ÏLœˆ'pþ<¼½ˆ‚ÊŠ~ïÞÇkcQ.;;ôèQ0ÆM€Ñ²|i¼ÐéŠã*Í3.‡È ”çr=ù¿€×ˆÏ7f?}µoß©>}$îîƒ_½âŠ?I¨T*K–,™˜˜èââIšÈ§N:÷ïßçñx)))™³Ï‡‡£V-ÄÇcÍüòKÁ|NOOܽ›v„fÍ Æ¬É°ó–/Ê<î2{»eöHd˜G:}<Ã$0ŒöÃßH[š.Ïå”äp\9œ,û+öêuåʨ7øùyNŸžñÖ¹sçtíÚ5“p$''?~ü@Íš5³(mS²$6lÀ?bÊ´l‰š5 àsêõ`$?ÙÛ Kq!ìâE?`½½½êÓÚ+S§N5~küýý3=²sçNã­Q£FekwÀ:uˆ&ï±dBY¼˜T¨ðq±#ý_É’ù2k&ìÞ0–Ì”lÙ²LûöšÄÄÿ–-ËØþæÍãE•*U2=rðàAãEæÅŽŒüý7ʖŽ{˜;7_þ98al )IDAT o_¸fØD;x0fÍÂøñù2k.E)T,,Åùýûkhúo¡09$$½ÑËËËø­yòäIÆÎ<à|8JóàÁƒœì‡Ð49>¿.Ö®ýqÆ”_kæÃÎ;XX²À¹víŠ}úÔê[N£p?d$Ó~šâtܸq•*U ‹«W¯ž“ÝfÍ0y2ƒ#!¡àý.BXí`aɚƋsøüg[·Æ?ybl)[¶¬ñ"ýåÀŠ+²R·n]N®gy.Dýú øq…âwQÁj KÖØ–+W}äHb0\Ÿ5ËØÒ¶m[ã…ŸŸŸV«Õét‹/^²dÉüùóŸÇ ìÑ£‡D"ЦM›Û·o·iÓæÆÆþ¦Ì;ÆŒóöí[OOÏEß}‡ÄD „üצ³E/W,,ÅmJŠ¿««|ôhv}¾ûî;¹Zóõõ •J_¼xAÂɳ3ÈäÅ3vÞÁÂbÍð¤Òz3g¸6c1d.käÎ;êÕ«—³©}ûö͘1ƒÃáìÞ½»R¥Jpw‡ñøÜ¬Yøp÷>”­²NXí`aÉ…?ýdW¡BÜãÇÏwìøüî»wïbcc‘Û ËÞ½{ DYµjUçÎÓZøC‡B£AÿþP©2?3uª5¿Î°ÚÁÂ’ >¿áüùnÎkÐh2Ý5N:ÔÉ&Ñ)€õë×0@«ÕN:õ—LgáÖ¬AÅŠxú™Ò>y‚µkñþ½y¾îÚԯɓQ¡lmñÃ8v ýú¡D ØÙ!}§l\ B—.èÐ={",,­}Û64lˆЬ¼½‘¾“eÃxy¡W/xzâï¿v½ƒ…Ńawݺ~ÀÝ+2Ýšþá¼\Æbé¨Tª‘ê<-\¸0këW¯¦m6={öcc Y?òø1ñðø¸Þ±b &Æ|"ÞÞ¤V-L ràÈôé$<œ¤¤ ‡“–±Q#2thšµNˆ—WÚõš5i¡Ÿ¤$Âá={!äåKBÓD.'„øxâëKØÜ?,,&òîäI?`½ƒƒ:>>c{ú¦zõêT±~{øðÿÏÏÚæ‘Zµpü8‘šZ0 6FËÂ’ÆûÀÀ~~Ñ·n©ããi¯\—.÷ïÏù‘à#GŽuë&’É¿y£W*wÕ¬©’ËyÉOVùm/XØz´,,p÷÷߯N €âp*õëyíZrpp®O•ëÚµDÓ¦‘W¯Þ_±"âêU•\@oÝù¾ ö……ñÿoïþBšŠâ8€ÿ\n3Y›ŽÒÊ©–4 0“þŠZZ*¦Ø–-ò- ½Eµ^‚^F=”jH`…I”+(]E)Ãå4ÁQRùw‹Èmt]ǪisÌi»ßÏÓîÙ½‡sîß9çÞsÌæ—SËp¬=qbW]Ýf­ÖÇkÙ3;´Úz=[âb˜Éyßhzî!ï Þš÷Tk|v6%æåñ½<–¦¦wׯ“Ëå´Ù&ÆiµN2 ÏÿcŒƒ±Ûy~¼*ö_Aì a£Ñý{ñ²eD$H’¼½ žTZºH Ð?>144C…ŒÃÁõØ> Ù=¶† ó–nx’2™ä{öÌpNÀ¦Z0ÄrÍrx"26¶¨¥egmítɆK1G œÖqéRÏ­[6½©Y¢¸¸cî¥Ã§÷m`àÉ‘#Ÿ †?Ê÷ôH•Ê€µrABÞœ&ŒŽN.+‹Œu—¬Q©6ž=›vê”/—‹åò’§O7h4a¼ß%yÜY¿~djg¶}mm+·nm Ÿž=k=zôûTªràÕ«å™™l⃼ dÙÙ»ºVíßÏb¬|!•î¾{7·ºZ s¡Ï‚÷;IY^—•…س&žnõÀЂ> ø±üØþ@ì v€?0Ï\7f6;m6÷á×7oD2™81Ñrÿ¾áÌ©R™\VfÒé–¦¦fétöÑѧO;¬ÖI§“/m¿vM$“½¿}»­²rIB‚0*j¼¯ÏÅ0k+*2/\ °0˽{W27@È;€Ó> õëÖ}p—´WUÕ*} I%%Ë7míîH$Y:Ï'¢æÂBŸ_ÔÜ\üø1c··ªTD´F¥ŠIO_³W¯WæÜ¼ùöâÅžêj"òZIh@Þœ¶bË–“3~Òµ$!A^P@D›/_ëíýòúuÆùóì_ñ¹¹í ãp, ‰(<"‚ý"N^PŸ“Ó}ãFŠZýw%sz;Á„Øà“ðÈH[?¯^í­©!"Çøx´Rùsb‚ž¤))}uu^+™û– b€¯Ø‘qîÜ??´eìöPêžx…ñ_‰ "3›ÿy¦µ¿?kÿ+jõê•Û¶ujµlç…¦Yãg¤«kðùó Mp[lˆÞ}xôhØh´Y,W®üüñƒ-Ì«¯_š–Ö˜‘Q«P4íØÁN¦°FL¦V•êaq±^­Îkh`G½V°n@<ÈÏJ$ùóÝàAÞ\X+ÌbøãØÑk»Î§ÒˆIEND®B`‚opengv/doc/addons/03_matlab.dox0000664016516101651610000001772113344612246015312 0ustar dimadima/** \page page_matlab The Matlab interface * * All algorithms are accessed from Matlab via one interface file only. The syntax is as follows: * *
    *
  • X = opengv ( method, data1, data2 ) *
  • X = opengv ( method, indices, data1, data2 ) *
  • X = opengv ( method, indices, data1, data2, prior ) *
* * where *
    *
  • method is a string that characterizes the algorithm to use. It can be one of the following: * \verbatim absolute pose methods: 'p2p', 'p3p_kneip', 'p3p_gao', 'epnp', 'p3p_kneip_ransac', 'p3p_gao_ransac', 'epnp_ransac', 'abs_nonlin_central', 'gp3p', 'gp3p_ransac', 'gpnp', 'abs_nonlin_noncentral', 'upnp'. relative pose methods: 'twopt', 'twopt_rotationOnly', 'rotationOnly', 'fivept_stewenius', 'fivept_nister', 'fivept_kneip', 'sevenpt', 'eightpt', 'eigensolver', 'rotationOnly_ransac', 'fivept_stewenius_ransac', 'fivept_nister_ransac', 'sevenpt_ransac', 'eightpt_ransac', 'eigensolver_ransac', 'rel_nonlin_central', 'sixpt', 'seventeenpt', 'ge', 'sixpt_ransac', 'seventeenpt_ransac', 'ge_ransac', 'rel_nonlin_noncentral'. point_cloud methods: 'threept_arun', 'threept_arun_ransac'. \endverbatim * *
  • data1, data2 are correspondences (each one of dimension 3xn or 6xn). They are 3xn in the central case (only containing normalized bearing vectors or 3D points), and 6xn for measurements in the non-central case, * where they then also contain the position of the camera in the body frame in rows 4:6. Note that there is no camera orientation with respect to the body frame in the matlab syntax, the bearing vectors are * supposed to be prerotated into the body frame (only rotated!). *
  • indices is a subset of correspondences that we plan to use for the computation. *
  • prior is a 3x1 (translation), 3x3 (rotation), or 3x4 ([R t]-transformation) holding a prior value for the transformation to compute. *
  • The return value X is a 3xnxm-matrix, where n is the second dimensionality of the solution space, and m is the number of solutions. n is one for methods that only compute a translation, 3 for methods that only compute a rotation, and 4 for methods that compute both rotation and translation (format: [R t]). *
* * Note that, for Ransac-methods, the indices of the inliers can now also be retrieved. Simply add one return parameter on the left-hand side arguments: [X, inliers] = opengv(...). The Matlab wrapper includes rather exhaustive checking of command validity. More algorithms are planned for inclusion. * * \section Examples * * The interface is probably explained easiest at the hand of a few examples. Let's say that we have a matrix P of size 3xn which contains n world points. Let's also assume that we have a matrix I of size 2xn which contains the corresponding 2D measurements in the image plane. Let us assume that our camera is perspective and that we have a calibration matrix K that contains the intrinsic parameters (standard upper triangular matrix). OpenGV expects normalized coordinates on the unit sphere, so we start by transforming the measurements. * \verbatim temp = K \ [I; ones(1,size(I,2))]; I_norms = sqrt(sum(temp.*temp)); I_normalized = temp ./ repmat(I_norms,3,1); \endverbatim * * We are now ready to call OpenGV to compute the camera pose. Let's say we want to use the EPnP method: * \verbatim X = opengv('epnp',P,I_normalized); R = X(:,1:3); t = X(:,4); \endverbatim * * Done! Ok, let's make things a bit more interesting, and assume that there are also outliers in the data. We simply have to switch to a Ransac method to take outliers into account! * \verbatim [X, inliers] = opengv('p3p_kneip_ransac',P,I_normalized); \endverbatim * * Note that this will also give use the indices of the inliers. * * Now let us also look at a non-central example to see how this works. We assume that we have a multi-camera system with two cameras. The cameras have the positions t1 and t2 inside the body-frame. The rotation from the camera frames to the body frame is R1 and R2, respectively. Camera 1 has intrinsic parameters K1, and camera 2 has intrinsic parameters K2. Now let us assume that there are correspondences in both views. Camera one measures the image points I1 which belong to the world points P1 (I1 is 2xn1 and P1 is 3xn1). Camera 2 measures the image points I2 which belong to the world points P2 (I2 is 2xn2 and P2 is 3xn2). Now let us start with normalizing the image points into direction vectors on the unit sphere: * \verbatim temp = K1 \ [I1; ones(1,size(I1,2))]; I1_norms = sqrt(sum(temp.*temp)); I1_normalized = temp ./ repmat(I1_norms,3,1); temp = K2 \ [I2; ones(1,size(I2,2))]; I2_norms = sqrt(sum(temp.*temp)); I2_normalized = temp ./ repmat(I2_norms,3,1); \endverbatim * * We then can compute the absolute pose of the multi-camera system by simply executing this command * \verbatim X = opengv('upnp',[P1 P2],[ R1*I1_normalized, R2*I2_normalized; repmat(t1,1,size(I1,2)), repmat(t2,1,size(I2,2)) ]); R = X(:,1:3); t = X(:,4); \endverbatim * * In order to handle outliers as well, simply switch to 'gp3p_ransac'. Now that you know how to handle 2D-3D registration in the central and non-central case, the 2D-2D registration case is also easily learned. Simply replace the world points by 2D measurements in another view. * * \section sec_benchmarks Automatic benchmarking of algorithms * * Perhaps the nicest thing about the Matlab-code is that it includes automatic benchmarks for all algorithms. The subfolder matlab/helpers contains useful functions for the benchmarks. * The most important ones are: * *
    *
  • create2D2DExperiment.m: Lets you create a random relative pose problem, meaning correspondences in two viewpoints using desired number of cameras, number of correspondences, * outlier ratio, and noise. It returns the observations in both viewpoints, plus the ground truth values for the relative transformation parameters. It automatically returns * measurement data for the central or the noncentral case depending on how many cameras are configured. *
  • create2D3DExperiment.m: Does pretty much the same thing, however for the absolute pose situation. *
  • evaluateRotationError.m/evaluateTransformationError.m: Computes the rotation/transformation error of multiple hypotheses by selecting the one that is closest to ground truth. *
  • perturb.m: puts a random perturbation on a transformation *
  • rodrigues.m / cayley2rot.m / rot2cayley.m: back and forth transformation to minimal rotation representations. *
  • transformEssentials.m: Transforms a set of multiple essential matrices into rotations. *
  • addNoise.m: Adds noise to a bearing vector by assuming a spherical camera and extracting the corresponding tangential plane. *
* * The main benchmark files are finally given by: * *
    *
  • benchmark_absolute_pose.m *
  • benchmark_absolute_pose_noncentral.m *
  • benchmark_relative_pose.m *
  • benchmark_relative_pose_noncentral.m *
* * opengv.cpp contains the interface itself. Some other files like opengv_donotuse.cpp are used for timing experiments (named benchmark_xxx_timing.m). They execute each problem 20 times so time can be measured sufficiently accurate without overhead from Matlab. opengv_experimental1.cpp and opengv_experimental2.cpp are used for some specific ransac experiments, they are not as important. * * The benchmarks are fairly well documented and self-explaining. They simply run multiple tests for each algorithm while going through increasing noise-levels, and finally plot the resulting mean and * median errors. Adding an algorithm or changing the set of algorithms for comparison is very easy, you simply have to modify the cell-arrays algorithms, indices, and names. They contain the internal * names of the algorithms that are being evaluated, the indices of the points to use from the experiment (allowing to use different (numbers of) points for each algorithm and random experiment), and * the names of the algorithms for the final plots. Comparing your new algorithm has never been easier :) */opengv/doc/addons/02_how_to_use.dox0000664016516101651610000007656313344612246016235 0ustar dimadima/** \page page_how_to_use How to use * * This page gives an introduction to the usage of OpenGV including a description of the interface and explicit examples. More information can be found in [17]. However, in order to have a smooth communication and full understanding of the functionality and documentation of the library, we first need to clearly define the meaning of a couple of words in the present context. * * \section sec_vocabulary Vocabulary * *
    *
  • Bearing vector: A bearing vector is defined to be a 3-vector with unit norm bearing at a spatial 3D point from a camera reference frame. It has 2 degrees of freedom, which are the azimuth and elevation in the camera reference frame. Because it has only two degrees of freedom, we frequently refer to it as a 2D information. It is normally expressed in a camera reference frame. *
  • Landmark: A landmark describes a 3D spatial point (usually expressed in a fixed frame called world reference frame). *
  • Camera: OpenGV assumes to be in the calibrated case, and landmark measurements are always given in form of bearing vectors in a camera frame. A camera therefore denotes a camera reference frame with a set of bearing vectors, all pointing from the origin to landmarks. The following figure shows a camera c with bearing vectors (in red). The bearing vectors are all lying on the unit-sphere centered around the camera. * * \image html central.png * \image latex central.pdf "" width=0.45\columnwidth * *
  • Viewpoint: You will notice that the documentation of the code very frequently talks about viewpoints instead of cameras. One of the advantages of OpenGV is that it can transparently handle both the central and the non-central case. The viewpoint is a generalization of a camera, and can contain an arbitrary number of cameras each one having it's own landmark-measurements (e.g. bearing vectors). A practical example of a viewpoint would be the set of images and related measurements captured by a fully-calibrated, rigid multi-camera rig with synchronized cameras, which therefore still represents a single (multi)-snapshot (i.e. viewpoint). Each camera has its own transformation to the viewpoint frame. In the central case the viewpoint simply contains a single camera with an identity transformation. The most general case-the generalized camera-can also be described by the viewpoint. Each bearing vector would then have it's own camera and related transformation. A generalized camera would hence be represented by an exhaustive multi-camera system. The following image shows a viewpoint vp (in blue) with three cameras c, c', and c'', each one containing its own bearing vector measurements. * * \image html noncentral.png * \image latex noncentral.pdf "" width=0.8\columnwidth * *
  • Pose: By a pose, we understand here the position and orientation of a viewpoint, either with respect to a fixed spatial reference frame called the "world" reference frame, or with respect to another viewpoint. *
  • Absolute Pose: By absolute pose, we understand the pose of a viewpoint in the world reference frame. *
  • Relative Pose: By relative pose, we understand the pose of a viewpoint with respect to another viewpoint. *
  • Correspondence: By a correspondence, we understand a pair of bearing-vectors pointing at the same landmark from different viewpoints (2D-2D correspondence), a bearing vector and a world-point it is pointing at (2D-3D correspondence), or a pair of expressions of the same landmark in different frames (3D-3D correspondence). *
* * \section sec_organization Organization of the library * * The library-structure is best analyzed at the hand of the namespace or directory hierarchy (as a matter of fact, there is no difference between the two): *
    *
  • opengv: contains generic things such as the types used throughout the library. *
  • opengv/math: contains a bunch of math functions that are used in different algorithms, mainly for root-finding and rotation-related stuff. *
  • opengv/absolute_pose: contains the absolute-pose methods. methods.hpp is the main-header that contains the method-declarations. You can also find a bunch of adapters here for interfacing with the algorithms (explained in the next section). The sub-folder modules contains declarations of internal methods. *
  • opengv/relative_pose: contains the relative-pose methods. methods.hpp is the main-header that contains the method-declarations. You can also find a bunch of adapters here for interfacing with the algorithms (explained in the next section). The sub-folder modules contains declarations of internal methods. *
  • opengv/point_cloud: contains the point-cloud alignment methods. Again, methods.hpp contains the declarations, and the folder contains adapters for interfacing (explained below). *
  • opengv/triangulation: contains the triangulation methods. *
  • opengv/sac: contains base-classes for sample-consensus methods and problems. So far, only the Ransac algorithm is implemented. *
  • opengv/sac_problems: contains sample-consensus problems derived from the base-class. Implements sample-consensus problems for point-cloud alignment and central as well as non-central absolute and relative-pose estimation. *
* * \section sec_interface Interface * * You will quickly notice that all methods in OpenGV use a variable called adapter as a function-call parameter. OpenGV is designed based on the adapter pattern. "Adapters" in OpenGV are used as "visitors" to all geometric vision methods. They contain the landmarks, bearing-vectors, poses, correspondences etc. used as an input to the different methods (or references to the alike), and allow to access those elements with a unified interface. Adapters are derived from a base-class that defines the unified interface and they have to implement the related functions for accessing bearing-vectors, world-points, camera-transformations, viewpoint-poses, etc. There are three adapter-base-classes: * *
    *
  • AbsoluteAdapterBase: Base-class for adapters holding 2D-3D correspondences for absolute-pose methods. *
  • RelativeAdapterBase: Base-class for adapters holding 2D-2D correspondences for relative-pose methods. *
  • PointCloudAdapterBase: Base-class for adapters holding 3D-3D correspondences for point-cloud alignment methods. *
* * The derived adapters have the task of transforming the data from the user-format to OpenGV types. This gives the library great flexibility. Users have to implement only a couple of adapters for the specific data-format they are using, and can then access the full functionality of the library. OpenGV currently contains adapters that simply hold references to OpenGV types (no transformation needed) plus adapters for mexArrays used within the Matlab-interface. Further adapters are planned, such as for instance an adapter for OpenCV keypoint and match-types including a camera model. The user would then be able to chose whether normalization of keypoints is done "on-demand" or "once for all" at the beginning, which is more efficient in sample-consensus problems. * * Note that adapters containing the tag "Central" in their name are adapters for a single camera (i.e. view-points with only one camera having identity transformation). Adapters having the tag "Noncentral" in their name are meant for view-points with multiple cameras (e.g., multi-camera systems, generalized cameras). * * Please check out the doxygen documentation on the above base-classes, they contain important documentation on the functions that need to be overloaded for a proper implementation of an adapter. * * \section sec_conventions Conventions, problem types, and examples * * As already mentioned, the entire library is assuming calibrated cameras/viewpoints, and it operates with 3D unit bearing vectors expressed in the camera frame. Calibrated means that the configuration of the multi-camera system (i.e. the inter-camera transformations) is known. The following introduces the different problems that can be solved with the library, and outlines the conventions for transformations (translations and rotations) in their context. Note that all problems have solutions for both the minimal and non-minimal cases, and may also be solved as sample-consensus or non-linear optimization problems. The code samples are mostly taken from the test files, which you can compile along with the library by setting BUILD_TESTS in CMakeLists.txt to ON. * *
    * *
  • Central absolute pose: The central absolute pose problem consists of finding the pose of a camera (e.g. viewpoint with a single camera) given a number of 2D-3D correspondences between bearing vectors in the camera frame and points in the world frame. The seeked transformation is given by the position \f$ \mathbf{t}_{c} \f$ of the camera seen from the world frame and the rotation \f$ \mathbf{R}_{c} \f$ from the camera to the world frame. This is what the algorithms return (or part of it), and what the adapters can hold as known or prior information. * * \image html absolute_central.png * \image latex absolute_central.pdf "" width=0.8\columnwidth * * The minimal variants are p2p (a solution for position if rotation is known), p3p_kneip [1], p3p_gao [2], and UPnP [19]. The non-minimal variants are epnp [4], and UPnP [19]. The non-linear optimization variant is called optimize_nonlinear. Here's how to use them: * \code // create the central adapter absolute_pose::CentralAbsoluteAdapter adapter( bearingVectors, points ); // Kneip's P2P (uses rotation from adapter) adapter.setR( knownRotation ); translation_t p2p_translation = absolute_pose::p2p( adapter, indices1 ); // Kneip's P3P transformations_t p3p_kneip_transformations = absolute_pose::p3p_kneip( adapter, indices2 ); // Gao's P3P transformations_t p3p_gao_transformations = absolute_pose::p3p_gao( adapter, indices2 ); // Lepetit's Epnp (using all correspondences) transformation_t epnp_transformation = absolute_pose::epnp(adapter); // UPnP (using all correspondences) transformations_t upnp_transformations = absolute_pose::upnp(adapter); // UPnP (using three correspondences) transformations_t upnp_transformations = absolute_pose::upnp( adapter, indices2 ); // non-linear optimization (using all correspondences) adapter.sett(initial_translation); adapter.setR(initial_rotation); transformation_t nonlinear_transformation = absolute_pose::optimize_nonlinear(adapter); \endcode * * p3p_kneip, p3p_gao, and epnp can also be used within a sample consensus context. The following shows how to do it: * \code // create the central adapter absolute_pose::CentralAbsoluteAdapter adapter( bearingVectors, points ); // create a Ransac object sac::Ransac ransac; // create an AbsolutePoseSacProblem // (algorithm is selectable: KNEIP, GAO, or EPNP) std::shared_ptr absposeproblem_ptr( new sac_problems::absolute_pose::AbsolutePoseSacProblem( adapter, sac_problems::absolute_pose::AbsolutePoseSacProblem::KNEIP ) ); // run ransac ransac.sac_model_ = absposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = maxIterations; ransac.computeModel(); // get the result transformation_t best_transformation = ransac.model_coefficients_; \endcode * * These examples are taken from test_absolute_pose.cpp and test_absolute_pose_sac.cpp. * *
  • Non-central absolute pose: The non-central absolute pose problem consists of finding the pose of a viewpoint given a number of 2D-3D correspondences between bearing vectors in multiple camera frames and points in the world frame. The seeked transformation is given by the position \f$ \mathbf{t}_{vp} \f$ of the viewpoint seen from the world frame and the rotation \f$ \mathbf{R}_{vp} \f$ from the viewpoint to the world frame. This is what the algorithms return, and what the adapters can hold as known or prior information. * * \image html absolute_noncentral.png * \image latex absolute_noncentral.pdf "" width=0.8\columnwidth * * The minimal variant is gp3p, and the non-minimal variant is gpnp [3]. UPnP can be used for both the minimal and the non-minimal case [19]. The non-linear optimization variant is still optimize_nonlinear (it handles both cases). Here's how to use them: * \code // create the non-central adapter absolute_pose::NoncentralAbsoluteAdapter adapter( bearingVectors, camCorrespondences, points, camOffsets, camRotations ); // Kneip's GP3P transformations_t gp3p_transformations = absolute_pose::gp3p( adapter, indices1 ); // Kneip's GPNP (using all correspondences) transformation_t gpnp_transformation = absolute_pose::gpnp(adapter); // UPnP (using all correspondences) transformations_t upnp_transformations = absolute_pose::upnp( adapter ); // UPnP (using only 3 correspondences) transformations_t upnp_transformations_3 = absolute_pose::upnp( adapter, indices1 ); // non-linear optimization adapter.sett(initial_translation); adapter.setR(initial_rotation); transformation_t nonlinear_transformation = absolute_pose::optimize_nonlinear(adapter); \endcode * * gp3p can also be used within a sample-consensus context. It remains an AbsolutePoseSacProblem, this one is usable for both the central and the non-central case. We simply have to set algorithm to GP3P: * \code // create the non-central adapter absolute_pose::NoncentralAbsoluteAdapter adapter( bearingVectors, camCorrespondences, points, camOffsets, camRotations ); // create a RANSAC object sac::Ransac ransac; // create a absolute-pose sample consensus problem (using GP3P as an algorithm) std::shared_ptr absposeproblem_ptr( new sac_problems::absolute_pose::AbsolutePoseSacProblem( adapter, sac_problems::absolute_pose::AbsolutePoseSacProblem::GP3P ) ); // run ransac ransac.sac_model_ = absposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = maxIterations; ransac.computeModel(); // get the result transformation_t best_transformation = ransac.model_coefficients_; \endcode * * These examples are taken from test_noncentral_absolute_pose.cpp and test_noncentral_absolute_pose_sac.cpp. * *
  • Central relative pose: The central relative pose problem consists of finding the pose of a camera (e.g. viewpoint with a single camera) with respect to a different camera given a number of 2D-2D correspondences between bearing vectors in the camera frames. The seeked transformation is given by the position \f$ \mathbf{t}_{c'}^{c} \f$ of the second camera seen from the first one and the rotation \f$ \mathbf{R}_{c'}^{c} \f$ from the second camera back to the first camera frame. This is what the algorithms return (or part of it), and what the adapters can hold as known or prior information. * * \image html relative_central.png * \image latex relative_central.pdf "" width=0.6\columnwidth * * There are many central relative-pose algorithms in the library. The minimal variants are twopt (in case the rotation is known), twopt_rotationOnly (in case there is only rotational change, and using only two points), fivept_stewenius [5], fivept_nister [6], and fivept_kneip [7]. The libary also contains non-minimal variants, namely rotationOnly (in case of pure-rotation change), sevenpt [8], eightpt [9,10] and the new eigensolver [11] methods. All of them except twopt, twopt_rotationOnly, and fivept_kneip can be used for an arbitrary number of correspondences (of course at least the minimal number). The non-linear optimization variant is again called optimize_nonlinear. Here's how to use most of them (we assume a regular situation here, and thus omit the rotationOnly algorithms): * \code // create the central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2 ); // Relative translation with only two point-correspondences // (no or known rotation) adapter.setR(knownRotation); translation_t twopt_translation = relative_pose::twopt( adapter, true, indices1 ); // Stewenius' 5-point algorithm complexEssentials_t fivept_stewenius_essentials = relative_pose::fivept_stewenius( adapter, indices2 ); // Nister's 5-point algorithm essentials_t fivept_nister_essentials = relative_pose::fivept_nister( adapter, indices2 ); // Kneip's 5-point algorithm rotations_t fivept_kneip_rotations = relative_pose::fivept_kneip( adapter, indices2 ); // the 7-point algorithm essentials_t sevenpt_essentials = relative_pose::sevenpt( adapter, indices3 ); // the 8-point algorithm essential_t eightpt_essential = relative_pose::eightpt( adapter, indices4 ); // Kneip's eigensolver adapter.setR(initial_rotation); eigensolver_rotation = relative_pose::eigensolver( adapter, indices5 ); // non-linear optimization (using all available correspondences) adapter.sett(initial_translation); adapter.setR(initial_rotation); transformation_t nonlinear_transformation = relative_pose::optimize_nonlinear(adapter); \endcode * * fivept_nister, fivept_stewenius, sevenpt, and eigthpt can also be used within a random-sample consensus scheme. It is done as follows: * \code // create the central relative adapter relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2 ); // create a RANSAC object sac::Ransac ransac; // create a CentralRelativePoseSacProblem // (set algorithm to STEWENIUS, NISTER, SEVENPT, or EIGHTPT) std::shared_ptr relposeproblem_ptr( new sac_problems::relative_pose::CentralRelativePoseSacProblem( adapter, sac_problems::relative_pose::CentralRelativePoseSacProblem::NISTER ) ); // run ransac ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = maxIterations; ransac.computeModel(); // get the result transformation_t best_transformation = ransac.model_coefficients_; \endcode * * These examples are taken from test_relative_pose.cpp and test_relative_pose_sac.cpp. There are also sample consensus problems for the case of pure-rotation, known rotation, or the eigensolver method. Feel free to explore opengv/sac_problems/relative_pose. * *
  • Non-central relative pose: The non-central relative pose problem consists of finding the pose of a viewpoint with respect to a different viewpoint given a number of 2D-2D correspondences between bearing vectors in multiple camera frames. The seeked transformation is given by the position \f$ \mathbf{t}_{vp'}^{vp} \f$ of the second viewpoint seen from the first one and the rotation \f$ \mathbf{R}_{vp'}^{vp} \f$ from the second viewpoint back to the first viewpoint frame. This is what the algorithms return (or part of it), and what the adapters can hold as known or prior information. * * \image html relative_noncentral.png * \image latex relative_noncentral.pdf "" width=0.8\columnwidth * * There are three non-central relative pose methods in the library, the 17-point algorithm by Li [12], the 6-point method by Stewenius [16], and the new generalized eigensolver [18]. The 17-point algorithm as well as the generalized eigensolver can be used with an arbitrary number of points. The 6-point algorithm is usable with only 6-points exactly. "optimize_nonlinear" is again able to also handle the non-central case. Here's how to use these methods: * \code // create the non-central relative adapter relative_pose::NoncentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, camOffsets, camRotations ); // 6-point algorithm rotations_t sixpt_rotations = relative_pose::sixpt( adapter, indices ); // generalized eigensolver (over all points) geOutput_t output; relative_pose::ge(adapter,output); translation_t ge_translation = output.translation.block<3,1>(0,0); rotation_t ge_rotation = output.rotation; // 17-point algorithm transformation_t seventeenpt_transformation = relative_pose::seventeenpt( adapter, indices ); // non-linear optimization (using all available correspondences) adapter.sett(initial_translation); adapter.setR(initial_rotation); transformation_t nonlinear_transformation = relative_pose::optimize_nonlinear(adapter); \endcode * * All algorithms are also available in a sample-consensus scheme: * \code // create the non-central relative adapter relative_pose::NoncentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, camCorrespondences1, camCorrespondences2, camOffsets, camRotations ); // create a RANSAC object sac::Ransac ransac; // create a NoncentralRelativePoseSacProblem std::shared_ptr< sac_problems::relative_pose::NoncentralRelativePoseSacProblem> relposeproblem_ptr( new sac_problems::relative_pose::NoncentralRelativePoseSacProblem( adapter, sac_problems::relative_pose::NoncentralRelativePoseSacProblem::SEVENTEENPT) ); // run ransac ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = maxIterations; ransac.computeModel(); // get the result transformation_t best_transformation = ransac.model_coefficients_; \endcode * * These examples are taken from test_noncentral_relative_pose.cpp and test_noncentral_relative_pose_sac.cpp. Simply set SEVENTEENPT to GE or SIXPT in order to use the alternative algorithms. * *
  • Triangulation of points: OpenGV contains two methods for triangulating points. They are currently only designed for the central case, and compute the position of a point expressed in the first camera given a 2D-2D correspondence between bearing vectors from two cameras. The methods reuse the relative adapter, which need to hold the transformation between the cameras given by the position \f$ \mathbf{t}_{c'}^{c} \f$ of the second camera seen from the first one and the rotation \f$ \mathbf{R}_{c'}^{c} \f$ from the second camera back to the first camera frame. * * \image html triangulation_central.png * \image latex triangulation_central.pdf "" width=0.6\columnwidth * * There are two methods, triangulate (linear) and triangulate2 (a fast non-linear approximation). They are used as follows: * \code // create a central relative adapter // (immediately pass translation and rotation) relative_pose::CentralRelativeAdapter adapter( bearingVectors1, bearingVectors2, translation, rotation ); // run method 1 point_t point = triangulation::triangulate( adapter, index ); //run method 2 point_t point = triangulation::triangulate2( adapter, index ); \endcode * * The example is taken from test_triangulation.cpp. * *
  • Alignment of two point-clouds: OpenGV also contains a method for aligning point-clouds. It is currently only designed for the central case, and computes the transformation between two frames given 3D-3D correspondences between points expressed in the two frames (here denoted by c and c', although it ain't necessarily need to be cameras anymore). The method returns the transformation between the frames given by the position \f$ \mathbf{t}_{c'}^{c} \f$ of the second frame seen from the first one and the rotation \f$ \mathbf{R}_{c'}^{c} \f$ from the second frame back to the first frame. * * \image html point_cloud.png * \image latex point_cloud.pdf "" width=0.6\columnwidth * * The method is called threept_arun, and it can be used for an arbitrary number of points (minimum three). There is also a non-linear optimization method again called optimize_nonlinear. The methods are used as follows: * \code // create the 3D-3D adapter point_cloud::PointCloudAdapter adapter( points1, points2 ); // run threept_arun transformation_t threept_transformation = point_cloud::threept_arun( adapter, indices ); // run the non-linear optimization over all correspondences transformation_t nonlinear_transformation = point_cloud::optimize_nonlinear(adapter); \endcode * * There is also a sample-consensus problem for the point-cloud alignment. It is set up as follows: * \code // create a 3D-3D adapter point_cloud::PointCloudAdapter adapter( points1, points2 ); // create a RANSAC object sac::Ransac ransac; // create the sample consensus problem std::shared_ptr relposeproblem_ptr( new sac_problems::point_cloud::PointCloudSacProblem(adapter) ); // run ransac ransac.sac_model_ = relposeproblem_ptr; ransac.threshold_ = threshold; ransac.max_iterations_ = maxIterations; ransac.computeModel(0); // return the result transformation_t best_transformation = ransac.model_coefficients_; \endcode * * These examples are taken from test_point_cloud.cpp and test_point_cloud_sac.cpp. * *
* * Note that there are more unit-tests in the test-directory. It shows the usage of all the methods contained in the library. * * \section sec_threshold Some words about the sample-consensus-classes * * All the above mentioned Ransac-methods make use of a number of super-classes such that only the basic functions need to be implemented in the derived SacProblem (SampleConsensusProblem). The basic functions are responsible for getting valid samples for model instantiation, model instantiation itself, as well as model verification. SamplesConsensusProblem is the base-class for any problem we want to solve, and contains a virtual interface for the basic methods that need to be implemented. The base-class SampleConsensus is then for the sample-consensus method itself, calling the basic functions. So far only the Ransac is implemented [15]. * * \subsection sec_ransac Ransac threshold * * Since the entire library is operating in 3D, we also need a way to compute and threshold reprojection errors in 3D. What we are looking at is the angle \f$ q \f$ between the original bearing-vector \f$ \mathbf{f}_{meas} \f$ and the reprojected one \f$ \mathbf{f}_{repr} \f$. By adopting a certain threshold angle \f$ q_{threshold} \f$, we hence constrain the \f$ \mathbf{f}_{repr} \f$ to lie within a cone of axis \f$ \mathbf{f}_{meas} \f$ and of opening angle \f$ q_{threshold} \f$. * * \image html reprojectionError.png * \image latex reprojectionError.pdf "" width=0.45\columnwidth * * The threshold-angle \f$ q_{threshold} \f$ can be easily obtained from classical reprojection error-thresholds expressed in pixels \f$ \psi \f$ by assuming a certain focal length \f$ l \f$. We then have \f$ q_{threshold} = \arctan{\frac{\psi}{l}} \f$. * * The threshold we are using in the end is still not quite this one, but a value derived from it in analogy with the computation of reprojection errors. The most efficient way to compute a "reprojection error" is given by taking the scalar product of \f$ \mathbf{f}_{meas} \f$ and \f$ \mathbf{f}_{repr} \f$, which equals to \f$ \cos q \f$. Since this value is between -1 and 1, and we actually want an error that minimizes to 0, we take \f$ \epsilon = 1 - \mathbf{f}_{meas}^{T}\mathbf{f}_{repr} = 1 - \cos q \f$. The threshold error is therefore given by * * \f$ \epsilon_{threshold} = 1 - \cos{q_{threshold}} = 1 - \cos({\arctan{\frac{\psi}{l}}}) \f$ * * In the ransac-examples in the test-folder, you will often see something like this. * \code ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); \endcode * * This notably corresponds to the above computation of our "reprojection-error"-threshold, with a focal length of 800.0 and a reprojection error in pixels of 0.5*sqrt(2.0). * * \section sec_multi The "Multi"-stuff * * As you go deeper into the code you might notice that there are a number of elements (mostly in the relative-pose context) that contain the tag "multi" in their name. The adapter base-class used here is called RelativeMultiAdapterBase. The idea of this adapter is to hold multiple sets of bearing-vector correspondences originating from pairs of cameras. A pair of cameras is, as the name says, a set of two cameras in different viewpoints. The correspondences are accessed via a multi-index (a pair-index referring to a specific pair of cameras, and a correspondence-index refering to the correspondence within the camera-pair). * * Subsets of camera-pairs can be identified in a number of problems, such as *
    *
  • Non-central relative pose (2 viewpoints): Non-central relative pose problems involving two viewpoints typically originate from motion-estimation with multi-camera rigs. In the special situation where the cameras are pointing in different directions, and where the motion between the viewpoints is not too big (a practically very relevant case), the correspondences are typically originating from the same camera in both viewpoints. We therefore can do a camera-wise grouping of the correspondences in the multi-camera system. The following situation contains four pairs given by the black, green, blue, and orange camera in both viewpoints: * * \image html nonoverlapping.png * \image latex nonoverlapping.pdf "" width=0.8\columnwidth * *
  • Central multi-viewpoint problems: By multi-viewpoint we understand here problems that involve more than two viewpoints. As indicated below, a problem of three central viewpoints for instance allows to identify three camera-pairs as well. The number of camera-pairs in an n-view problem amounts to the combination of 2 out of n, meaning n*(n-1)/2. For the below example, we could have tha camera pairs (c,c'), (c',c''), and (c'',c). The first pair would have a set of correspondences originating from points p1 and p4, the second one from p2 and p4, and the third one from p3 and p4. * * \image html multi_viewpoint.png * \image latex multi_viewpoint.pdf "" width=0.8\columnwidth * *
* * The multi-adapters keep track of these camera-pair-wise correspondence groups. The benefit of it appears when moving towards random sample-consensus schemes. Have a look at the "opengv/sac/"-folder, it contains the MultiSampleConsensus, MultiRansac, and MultiSampleConsensusProblem classes. They employ the multi-indices, and the derived MultiSampleConsensusProblems exploit the fact that the correspondences are grouped: * *
    *
  • The MultiNoncentralRelativePoseSacProblem is for non-central, non-overlapping viewpoints with little change, and exploits the grouping in order to do homogeneous sampling of correspondences over the cameras. As an example, imagine we are computing the relative pose of a non-overlapping multi-camera rig with two cameras facing opposite directions. In terms of accuracy, it doesn't make sense to sample 16-points in one camera and one point in the other. We preferrably would like to sample 8 points in one camera, and 9 in the other. This is exactly what MultiNoncentralRelativePoseSacProblem is able to do. It uses the derived adapter NoncentralRelativeMultiAdapter. *
  • In the multi viewpoint case, one could of course solve a central relative pose problem for each camera-pair individually. The idea of MultiCentralRelativePoseSacProblem is to benefit from a joint solution of multiple relative-pose problems. In the above three-view problem for instance, we can exploit additional constraints around the individual transformations such as cycles of rotations returning identity, and cycles of translations returning zero. The corresponding adapter is called CentralRelativeMultiAdapter. *
* * All this stuff is highly experimental, so you probably shouldn't pay too much attention to it for the moment ;) * */ opengv/doc/addons/05_contact.dox0000664016516101651610000000021613344612246015476 0ustar dimadima/** \page page_contact Contact * * For any questions or inquiries, please contact: * \verbatim kneip.laurent@gmail.com \endverbatim * */ opengv/doc/addons/01_installation.dox0000664016516101651610000002470313635643413016552 0ustar dimadima/** \page page_installation Installation * * \section sec_installation_0_5 Before you start * * If you are only interested in using the library under Matlab, now there is a precompiled mex-library for 64-bit systems available. You can download it from: * \verbatim Windows: http://laurentkneip.github.io/publications/opengv.mexw64 Mac OSX: http://laurentkneip.github.io/publications/opengv.mexmaci64 \endverbatim * * These versions have been added around March 2016, so please be aware that later additions may not be included in this distribution. You can go immediately to \ref page_matlab "Use under Matlab" to receive further instructions on the Matlab interface. * * \section sec_installation_1 Downloading the source code * * OpenGV is freely available under * \verbatim https://github.com/laurentkneip/opengv \endverbatim * * You may first have to register on github.com. You can just download a zip-file with the code, but we strongly recommend that you make yourself familiar with git. Git is a distributed version-control and source code management system. By using git to clone the repository locally, you can easily get updates at a later stage, and also facilitate the integration of own improvements or extensions into the original repository on github. This is done using the pull-request mechanism. * * To clone the library under Mac OSX or Linux, simply type (assuming that git is installed): * \verbatim git clone https://github.com/laurentkneip/opengv \endverbatim * * Under Windows you probably have a similar option. More information about git can be found here: * \verbatim http://git-scm.com/ \endverbatim * * Follow the "Try git" link for an amazing interactive tutorial. * * \section sec_installation_2 Installation under Linux * *
    *
  • Setup the required tools for compilation of standard libraries under Linux (gcc compiler etc). Type: * \verbatim sudo apt-get install build-essential \endverbatim * *
  • Install cmake. CMake is a cross-platform, open-source build system used for pretty much anything in the compilation process for the compilation/linking of the library. Type: * \verbatim sudo apt-get install cmake \endverbatim * * *
  • Install eigen3. Eigen3 is a powerful linear algebra library used for all computations in OpenGV. You can either use an installed version of a local install (unzipped version of Eigen3 downloaded from Eigen website). * \verbatim sudo apt-get install cmake libeigen3-dev \endverbatim * *
  • Go to the top-level directory of OpenGV. Type: * \verbatim mkdir build && cd build && cmake .. && make \endverbatim * * If a message like "Could NOT find Eigen (missing: EIGEN_INCLUDE_DIR EIGEN_VERSION_OK)" appears. It's certainly because that you does not have Eigen3 installed on your computer system path. You can specify to cmake the path where Eigen is located by adding: \verbatim mkdir build && cd build && cmake .. -DEIGEN_INCLUDE_DIR:STRING="EigenIncludePath" && make \endverbatim * *
  • Done. The default configuration does not build the tests or python-wrappers, please set the according variables in CMakeLists.txt to ON if you desire the tests or python-wrappers to be built as well. *
* * \section sec_installation_3 Installation under Windows * *
    *
  • We need a suitable compiler for C++. We chose Visual Studio Express, which is free. Google for "Microsoft Visual Studio Express", it should be one of the first links. Make sure you download and install the "Windows Desktop version". If you are in a school setting without Administrator rights, just go to your local IT guy and ask him to install Microsoft Visual Studio on your machine. * *
  • We also need CMake under Windows. Go to: * \verbatim http://www.cmake.org/ \endverbatim * * and download the latest version. In a school setting without administrator rights, chose to download the zip-file. Extract it somewhere. *
  • Open a new Developer Command Prompt for VS2012 and make sure all VS path variables are correctly set by checking the output of PATH. We also need to add the cmake-tools to the path. Add it by typing * \verbatim cd C:\\bin PATH=%PATH%;%cd%; \endverbatim * *
  • Go to the opengv directory and add a build folder *
  • Now go to the * \verbatim opengv\build \endverbatim * * directory, and setup the build process by typing: * \verbatim cmake -G "Visual Studio 11" .. \endverbatim * * You need to add the correct generator for your Visual Studio version. I downloaded Visual Studio 2012, so it's 11 :) *
  • Now build the library by typing: * \verbatim msbuild opengv.sln /p:Configuration=Release \endverbatim * * inside the build directory. While there is not a single warning under Linux, there are thousands of warnings under Windows :) If anyone knows the reason, please let us know. * *
  • Note that we Eigen dependency is not longer included. It is better to get a fresh download of Eigen on your computer, and specify to cmake the Eigen include path with -DEIGEN_INCLUDE_DIR="path". *
* * \section sec_installation_35 Installation under OSX * * Has been succesfully tested as well. * *
    *
  • Install homebrew: http://brew.sh/ *
  • Type: "brew install cmake eigen" *
  • Compile using normal cmake procedure. *
* * \section sec_installation_36 Installing OpenGV on the host OS * * Installation on the host OS (including the headers) can be activated by simply launching the install target. * By using "sudo make install" on Linux and OSX and by compiling the install target on the opengv Visual Studio solution in Windows. Sudo is required for system install. * You can choose to have a local installation path by setting the cmake variable CMAKE_INSTALL_PREFIX to the path of your choice by using -DCMAKE_INSTALL_PREFIX:STRING="YourInstallPath" in the cmake command line. \verbatim cmake ../opengv -DEIGEN_INCLUDE_DIR="EigenIncludePath" -DBUILD_TESTS=ON -DCMAKE_INSTALL_PREFIX="YourInstallPath" make make install #sudo not required since we use a local installation \endverbatim * * \section sec_installation_4 Installing the Matlab-wrapper (Windows-version) * *
    *
  • First setup the compiler from Matlab. Go to the matlab console and type * \verbatim mex -setup \endverbatim * * and chose the right compiler by following the instructions. You will have to chose the same compiler than the one you used for compiling the opengv library before-hand. Under Windows you might also * run into the following problem. Depending on the distribution (e.g. R2012b), Matlab does not yet "know" your compiler (e.g. Visual Studio 2012), so you will have to additionally follow the instructions under * \verbatim http://jimdavid.blogspot.com.au/2012/12/matlab-2012b-mex-setup-with-vs2012.html \endverbatim * * to get things running. Also note that the Express compilers are not supported by Matlab, we ran into some issues when trying to use them. Please report if you have a solution to that. *
  • Once this is done, you can compile the mex-file by going to the opengv/matlab folder and typing in the console * \verbatim mex -I../include -I../EigenIncludePath -L../build/lib/Release -lopengv opengv.cpp \endverbatim * *
  • An additional note on 64-bit Windows/Matlab systems: If you have a Matlab version that is 64-bit, you will have to also compile OpenGV in 64-bit. You will have to follow * two steps for this under Windows. The first one is to make sure that you open an x64 native tools command prompt to make the x64 Visual Studio compiler visible. The second one * is to-when running cmake-extend the generator name by " Win64". The final command to run cmake finally looks as follows: * \verbatim cmake -G "Visual Studio 11 Win64" .. \endverbatim * * The actual build command stays the same. *
* * \section sec_installation_5 Installing the Matlab-wrapper (Linux-version) * * The following has been tested under Ubuntu 12.04 and a recent Matlab edition (>2013) (thanks to Oliver Dunkley for providing this information). * *
    *
  • Install Matlab with the provided installer, and then add the matlab-support package through the package-repositories. This basically takes care * of setting all the compiler stuff, adding a launcher, etc. *
  • In order to make Matlab know about the shared object opengv.so, the path to opengv.so has to be added to LD_LIBRARY_PATH. Open .bashrc and add the line * \verbatim export LD_LIBRARY_PATH=/build/lib:$LD_LIBRARY_PATH \endverbatim * * and then start Matlab from the terminal, it'll know about opengv ... *
  • Go to the opengv/matlab-folder inside Matlab, and issue the command * \verbatim mex -I../include -I../EigenIncludePath -L../build/lib -lopengv opengv.cpp -cxx \endverbatim * * Note the lib directory does not contain a Release subfolder under linux, and that the -cxx option has to be added. *
* * \section sec_installation_6 Installing the Matlab-wrapper (OSX-version) * * To compile the Matlab interface under OSX, use the same command as under Windows, with adapted library folder (-L../build/lib instead of -L../build/lib/Release). You of course need to make sure again that Matlab knows where to find the library, and that a suitable compiler is set up in Matlab as well. * * \section sec_installation_7 Installing the python wrappers * * The Python wrappers depend on the pybind11 library, which is included as a git submodule. * To get it, run \verbatim git submodule update --init --recursive \endverbatim * With that done, the compliation of the Python wrappers can be enabled by setting the option BUILD_PYTHON to ON. * The especific version of Python to target can be set using the option PYBIND11_PYTHON_VERSION. * For example, \verbatim cmake ../opengv -DBUILD_PYTHON=ON -DPYBIND11_PYTHON_VERSION=3.6 \endverbatim * Note that the python wrappers currently only allow access to the central methods. * * \section sec_installation_8 Using the OpenGV inside your cmake c++ project * * Once your have a system or local install of opengv you can use it in your own project. * In your cmake file, add the search for the opengv library: \verbatim find_package(opengv REQUIRED) if (opengv_FOUND) add_executable(main_opengv_demo main.cpp) target_link_libraries(main_opengv_demo opengv) endif (opengv_FOUND) \endverbatim * * Then run cmake for your project (if you are using a local install of opengv, you can specify where the library is located by using -Dopengv_DIR: \verbatim cmake ../myproject -DCMAKE_BUILD_TYPE=RELEASE -Dopengv_DIR:STRING=/home/Foo/Documents/Dev/opengv_Build/install/CMake/ \endverbatim */ opengv/doc/addons/06_references.dox0000664016516101651610000000732213344612246016172 0ustar dimadima/** \page page_references References * [1] L. Kneip, D. Scaramuzza, R. Siegwart, "A Novel Parametrization of the Perspective-Three-Point Problem for a Direct Computation of Absolute Camera Position and Orientation", Proc. of The IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Colorado Springs, USA. June 2011. [2] X. Gao, X. Hou, J. Tang, H. Cheng. "Complete solution classification for the perspective-three-point problem", IEEE Transactions on Pattern Analysis and Machine Intelligence, 25(8):930–943, 2003. [3] L. Kneip, P. Furgale, R. Siegwart, "Using Multi-Camera Systems in Robotics: Efficient Solutions to the NPnP Problem", Proc. of The IEEE International Conference on Robotics and Automation (ICRA), Karlsruhe, Germany. May 2013. [4] V. Lepetit, F. Moreno-Noguer, P. Fua. "Epnp: An accurate O(n) solution to the pnp problem", International Journal of Computer Vision (IJCV), 81(2):578–589, 2009. [5] H. D. Stewénius, C. Engels, D. Nistér. "Recent developments on direct relative orientation", ISPRS Journal of Photogrammetry and Remote Sensing, 60(4):284–294, 2006. [6] D. Nistér, "An efficient solution to the five-point relative pose problem", IEEE Transactions on Pattern Analysis and Machine Intelligence (PAMI), 26(6):756–777, 2004. [7] L. Kneip, R. Siegwart, M. Pollefeys, "Finding the Exact Rotation Between Two Images Independently of the Translation", Proc. of The European Conference on Computer Vision (ECCV), Florence, Italy. October 2012. [8] R. Hartley, A. Zisserman. "Multiple View Geometry in Computer Vision", Cambridge University Press, New York, NY, USA, second edition, 2004. [9] H. Longuet-Higgins, "Readings in computer vision: issues, problems, principles, and paradigms", Morgan Kaufmann Publishers Inc., San Francisco, CA, USA, 1987. [10] R. Hartley, "In Defense of the Eight-Point Algorithm", IEEE Transactions on Pattern Analysis and Machine Intelligence (PAMI), 19(6):580–593, 1997. [11] L. Kneip, S. Lynen, "Direct Optimization of Frame-to-Frame Rotation", Proc. of The International Conference on Computer Vision (ICCV), Sydney, Australia. December 2013. (Accepted for publication) [12] H. Li, R. Hartley, J. Kim, "A Linear Approach to Motion Estimation Using Generalized Camera Models", Proc. of The IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Anchorage, Alaska, USA. June 2008. [13] K.S. Arun, T.S. Huang, S.D. Blostein, "Least-Squares Fitting of Two 3-D Point Sets", IEEE Transactions on Pattern Analysis and Machine Intelligence (PAMI), 9(5), 698-700, 1987. [14] A. Cayley. "About the algebraic structure of the orthogonal group and the other classical groups in a field of characteristic zero or a prime characteristic", Reine Angewandte Mathematik, 32, 1846. [15] M. Fischler, R. Bolles, "Random sample consensus: a paradigm for model fitting with applications to image analysis and automated cartography", Communications of the ACM, 24(6):381–395, 1981. [16] H. Stewenius, D. Nister, M. Oskarsson, K. Aström, "Solutions to Minimal Generalized Relative Pose Problems", Workshop on omni-directional vision, 2005. [17] L. Kneip, P. Furgale, "OpenGV: A unified and generalized approach to real-time calibrated geometric vision", Proc. of The IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China. May 2014. [18] L. Kneip, H. Li, "Efficient Computation of Relative Pose for Multi-Camera Systems", In Proc. of the IEEE Conference on Computer Vision and Pattern Recognition (CVPR), Columbus, USA. June 2014. [19] L. Kneip, H. Li, Y. Seo, "UPnP: An optimal O(n) solution to the absolute pose problem with universal applicability", In Proc. of The European Conference on Computer Vision (ECCV), Zurich, Switzerland. September 2014. * */ opengv/Makefile.ros0000664016516101651610000000005113344612246013245 0ustar dimadimainclude $(shell rospack find mk)/cmake.mkopengv/include/0000775016516101651610000000000013344612246012432 5ustar dimadimaopengv/include/opengv/0000775016516101651610000000000013344612246013730 5ustar dimadimaopengv/include/opengv/point_cloud/0000775016516101651610000000000013344612246016247 5ustar dimadimaopengv/include/opengv/point_cloud/PointCloudAdapter.hpp0000664016516101651610000001056513344612246022350 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file PointCloudAdapter.hpp * \brief Adapter-class for passing 3D point correspondences. Maps * opengv types back to opengv types. */ #ifndef OPENGV_POINTCLOUDADAPTER_HPP_ #define OPENGV_POINTCLOUDADAPTER_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the point-cloud alignment methods. */ namespace point_cloud { /** * Check the documentation of the parent-class to understand the meaning of * a PointCloudAdapter. This child-class is used for holding * data in form of references to opengv-types. */ class PointCloudAdapter : public PointCloudAdapterBase { private: using PointCloudAdapterBase::_t12; using PointCloudAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ PointCloudAdapter( const points_t & points1, const points_t & points2 ); /** * \brief Constructor. See protected class-members to understand parameters */ PointCloudAdapter( const points_t & points1, const points_t & points2, const rotation_t & R12 ); /** * \brief Constructor. See protected class-members to understand parameters */ PointCloudAdapter( const points_t & points1, const points_t & points2, const translation_t & t12, const rotation_t & R12 ); /** * Destructor */ virtual ~PointCloudAdapter(); //Access of correspondences /** See parent-class */ virtual opengv::point_t getPoint1( size_t index ) const; /** See parent-class */ virtual opengv::point_t getPoint2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; private: /** Reference to the 3D-points in frame 1 */ const points_t & _points1; /** Reference to the 3D-points in frame 2 */ const points_t & _points2; }; } } #endif /* OPENGV_POINTCLOUDADAPTER_HPP_ */ opengv/include/opengv/point_cloud/MAPointCloud.hpp0000664016516101651610000001005613344612246021260 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MAPointCloud.hpp * \brief Adapter-class for passing 3D point correspondences. Maps * matlab types to opengv types. */ #ifndef OPENGV_MAPOINTCLOUD_HPP_ #define OPENGV_MAPOINTCLOUD_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the point-cloud alignment methods. */ namespace point_cloud { /** * Check the documentation of the parent-class to understand the meaning of * a PointCloudAdapter. This child-class is used for holding * data in form of pointers to matlab-data. */ class MAPointCloud : public PointCloudAdapterBase { private: using PointCloudAdapterBase::_t12; using PointCloudAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ MAPointCloud( const double * points1, const double * points2, int numberPoints1, int numberPoints2 ); /** * Destructor */ virtual ~MAPointCloud(); //Access of correspondences /** See parent-class */ virtual opengv::point_t getPoint1( size_t index ) const; /** See parent-class */ virtual opengv::point_t getPoint2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; private: /** A pointer to the points in frame 1 */ const double * _points1; /** A pointer to the points in frame 2 */ const double * _points2; /** The number of points in frame 1 */ int _numberPoints1; /** The number of points in frame 2 */ int _numberPoints2; }; } } #endif /* OPENGV_MAPOINTCLOUD_HPP_ */ opengv/include/opengv/point_cloud/methods.hpp0000664016516101651610000001315513344612246020430 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file point_cloud/methods.hpp * \brief Methods for computing the transformation between two frames that * contain point-clouds. */ #ifndef OPENGV_POINT_CLOUD_METHODS_HPP_ #define OPENGV_POINT_CLOUD_METHODS_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the point-cloud alignment methods. */ namespace point_cloud { /** * \brief Compute the transformation between two frames containing point clouds, * following Arun's method [13]. Using all available correspondences. * * \param[in] adapter Visitor holding world-point correspondences. * \return Transformation from frame 2 back to frame 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of frame 2 seen from * frame 1, and \f$ \mathbf{R} \f$ being the rotation from * frame 2 to frame 1). */ transformation_t threept_arun( const PointCloudAdapterBase & adapter ); /** * \brief Compute the transformation between two frames containing point clouds, * following Arun's method [13]. * * \param[in] adapter Visitor holding world-point correspondences. * \param[in] indices Indices of the correspondences used for deriving the * transformation. * \return Transformation from frame 2 back to frame 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of frame 2 seen from * frame 1, and \f$ \mathbf{R} \f$ being the rotation from * frame 2 to frame 1). */ transformation_t threept_arun( const PointCloudAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the transformation between two frames containing point clouds * using nonlinear optimization. Using all available correspondences. * * \param[in] adapter Visitor holding world-point correspondences, plus the * initial values. * \return Transformation from frame 2 back to frame 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of frame 2 seen from * frame 1, and \f$ \mathbf{R} \f$ being the rotation from * frame 2 to frame 1). */ transformation_t optimize_nonlinear( PointCloudAdapterBase & adapter ); /** * \brief Compute the transformation between two frames containing point clouds. * Using nonlinear optimization. * * \param[in] adapter Visitor holding world-point correspondences, plus the * initial values. * \param[in] indices Indices of the correspondences used for optimization. * \return Transformation from frame 2 back to frame 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of frame 2 seen from * frame 1, and \f$ \mathbf{R} \f$ being the rotation from * frame 2 to frame 1). */ transformation_t optimize_nonlinear( PointCloudAdapterBase & adapter, const std::vector & indices ); } } #endif /* OPENGV_POINT_CLOUD_METHODS_HPP_ */ opengv/include/opengv/point_cloud/PointCloudAdapterBase.hpp0000664016516101651610000001416013344612246023136 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file PointCloudAdapter.hpp * \brief Adapter-class for passing 3D point correspondences. */ #ifndef OPENGV_POINTCLOUDADAPTERBASE_HPP_ #define OPENGV_POINTCLOUDADAPTERBASE_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the point-cloud alignment methods. */ namespace point_cloud { /** * The PointCloudAdapterBase is the base-class for the visitors to the * point-cloud alignment methods. It provides a unified interface to * opengv-methods to access point correspondences and priors or known variables * for the alignment. Derived classes may hold the data in any user-specific * format, and adapt to opengv-types. */ class PointCloudAdapterBase { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. */ PointCloudAdapterBase( ) : _t12(Eigen::Vector3d::Zero()), _R12(Eigen::Matrix3d::Identity()) {}; /** * \brief Constructor. * \param[in] R12 A prior or known value for the rotation from frame 2 to * frame 1. */ PointCloudAdapterBase( const rotation_t & R12 ) : _t12(Eigen::Vector3d::Zero()), _R12(R12) {}; /** * \brief Constructor. * \param[in] t12 A prior or known value for the position of frame 2 seen * from frame 1. * \param[in] R12 A prior or known value for the rotation from frame 2 * to frame 1. */ PointCloudAdapterBase( const translation_t & t12, const rotation_t & R12 ) : _t12(t12), _R12(R12) {}; /** * \brief Destructor. */ virtual ~PointCloudAdapterBase() {}; //Access of correspondences /** * \brief Retrieve the 3D-point of a correspondence in frame 1. * \param[in] index The serialized index of the correspondence. * \return The corresponding 3D-point. */ virtual opengv::point_t getPoint1( size_t index ) const = 0; /** * \brief Retrieve the 3D-point of a correspondence in frame 2. * \param[in] index The serialized index of the correspondence. * \return The corresponding 3D-point. */ virtual opengv::point_t getPoint2( size_t index ) const = 0; /** * \brief Retrieve the number of correspondences. * \return The number of correspondences. */ virtual size_t getNumberCorrespondences() const = 0; /** * \brief Retrieve the weight of a correspondence. The weight is supposed to * reflect the quality of a correspondence, and typically is between * 0 and 1. * \param[in] index The serialized index of the correspondence. * \return The corresponding weight. */ virtual double getWeight( size_t index ) const = 0; //Access of priors or known values /** * \brief Retrieve the prior or known value for the relative position. * \return The prior or known value for the position. */ virtual opengv::translation_t gett12() const { return _t12; }; /** * \brief Set the prior or known value for the relative position. * \param[in] t12 The prior or known value for the position. */ virtual void sett12(const translation_t & t12) { _t12 = t12; }; /** * \brief Retrieve the prior or known value for the relative rotation. * \return The prior or known value for the rotation. */ virtual opengv::rotation_t getR12() const { return _R12; }; /** * \brief Set the prior or known value for the relative rotation. * \param[in] R12 The prior or known value for the rotation. */ virtual void setR12(const rotation_t & R12) { _R12 = R12; }; public: /** Prior or known value for the position of frame 2 seen from frame 1. * Initialized to zero if not provided. */ translation_t _t12; /** Prior or known value for the rotation from frame 2 to frame 1. * Initialized to identity if not provided. */ rotation_t _R12; }; } } #endif /* OPENGV_POINTCLOUDADAPTERBASE_HPP_ */ opengv/include/opengv/triangulation/0000775016516101651610000000000013344612246016610 5ustar dimadimaopengv/include/opengv/triangulation/methods.hpp0000664016516101651610000000731013344612246020765 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file triangulation/methods.hpp * \brief Some triangulation methods. Not exhaustive. */ #ifndef OPENGV_TRIANGULATION_METHODS_HPP_ #define OPENGV_TRIANGULATION_METHODS_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the triangulation methods. */ namespace triangulation { /** * \brief Compute the position of a 3D point seen from two viewpoints. Linear * Method. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * relative transformation. * \param[in] index The index of the correspondence being triangulated. * \return The 3D point expressed in the first viewpoint. */ point_t triangulate( const relative_pose::RelativeAdapterBase & adapter, size_t index ); /** * \brief Compute the position of a 3D point seen from two viewpoints. Fast * non-linear approximation (closed-form). * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * relative transformation. * \param[in] index The index of the correspondence being triangulated. * \return The 3D point expressed in the first viewpoint. */ point_t triangulate2( const relative_pose::RelativeAdapterBase & adapter, size_t index ); } } #endif /* OPENGV_TRIANGULATION_METHODS_HPP_ */ opengv/include/opengv/types.hpp0000664016516101651610000001465213344612246015615 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file types.hpp * \brief A collection of variables used in geometric vision for the * computation of calibrated absolute and relative pose. */ #ifndef OPENGV_TYPES_HPP_ #define OPENGV_TYPES_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** A 3-vector of unit length used to describe landmark observations/bearings * in camera frames (always expressed in camera frames) */ typedef Eigen::Vector3d bearingVector_t; /** An array of bearing-vectors */ typedef std::vector > bearingVectors_t; /** A 3-vector describing a translation/camera position */ typedef Eigen::Vector3d translation_t; /** An array of translations */ typedef std::vector > translations_t; /** A rotation matrix */ typedef Eigen::Matrix3d rotation_t; /** An array of rotation matrices as returned by fivept_kneip [7] */ typedef std::vector > rotations_t; /** A 3x4 transformation matrix containing rotation \f$ \mathbf{R} \f$ and * translation \f$ \mathbf{t} \f$ as follows: * \f$ \left( \begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array} \right) \f$ */ typedef Eigen::Matrix transformation_t; /** An array of transformations */ typedef std::vector > transformations_t; /** A 3-vector containing the cayley parameters of a rotation matrix */ typedef Eigen::Vector3d cayley_t; /** A 4-vector containing the quaternion parameters of rotation matrix */ typedef Eigen::Vector4d quaternion_t; /** Essential matrix \f$ \mathbf{E} \f$ between two viewpoints: * * \f$ \mathbf{E} = \f$ skew(\f$\mathbf{t}\f$) \f$ \mathbf{R} \f$, * * where \f$ \mathbf{t} \f$ describes the position of viewpoint 2 seen from * viewpoint 1, and \f$\mathbf{R}\f$ describes the rotation from viewpoint 2 * to viewpoint 1. */ typedef Eigen::Matrix3d essential_t; /** An array of essential matrices */ typedef std::vector > essentials_t; /** An essential matrix with complex entires (as returned from * fivept_stewenius [5]) */ typedef Eigen::Matrix3cd complexEssential_t; /** An array of complex-type essential matrices */ typedef std::vector< complexEssential_t, Eigen::aligned_allocator< complexEssential_t> > complexEssentials_t; /** A 3-vector describing a point in 3D-space */ typedef Eigen::Vector3d point_t; /** An array of 3D-points */ typedef std::vector > points_t; /** A 3-vector containing the Eigenvalues of matrix \f$ \mathbf{M} \f$ in the * eigensolver-algorithm (described in [11]) */ typedef Eigen::Vector3d eigenvalues_t; /** A 3x3 matrix containing the eigenvectors of matrix \f$ \mathbf{M} \f$ in the * eigensolver-algorithm (described in [11]) */ typedef Eigen::Matrix3d eigenvectors_t; /** EigensolverOutput holds the output-parameters of the eigensolver-algorithm * (described in [11]) */ typedef struct EigensolverOutput { EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** Position of viewpoint 2 seen from viewpoint 1 (unscaled) */ translation_t translation; /** Rotation from viewpoint 2 back to viewpoint 1 */ rotation_t rotation; /** The eigenvalues of matrix \f$ \mathbf{M} \f$ */ eigenvalues_t eigenvalues; /** The eigenvectors of matrix matrix \f$ \mathbf{M} \f$ */ eigenvectors_t eigenvectors; } eigensolverOutput_t; /** GeOutput holds the output-parameters of ge */ typedef struct GeOutput { EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** Homogeneous position of viewpoint 2 seen from viewpoint 1 */ Eigen::Vector4d translation; /** Rotation from viewpoint 2 back to viewpoint 1 */ rotation_t rotation; /** The eigenvalues of matrix \f$ \mathbf{G} \f$ */ Eigen::Vector4d eigenvalues; /** The eigenvectors of matrix matrix \f$ \mathbf{G} \f$ */ Eigen::Matrix4d eigenvectors; } geOutput_t; } #endif /* OPENGV_TYPES_HPP_ */ opengv/include/opengv/Indices.hpp0000664016516101651610000000773513344612246016033 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file Indices.hpp * \brief Generic functor base for use with the Eigen-nonlinear optimization * toolbox. */ #ifndef OPENGV_INDICES_HPP_ #define OPENGV_INDICES_HPP_ #include #include #include using namespace std; using namespace Eigen; /** * \brief The namespace of this library. */ namespace opengv { /** * Index class used internally so we can efficiently access either all or * just a subset of the indices, using the same syntax */ struct Indices { /** Indexing into vector of indices? */ bool _useIndices; /** Pointer to a vector of indices (if used) */ const std::vector * _indices; /** The number of correspondences */ size_t _numberCorrespondences; /** * \brief Constructor using index-vector. * \param[in] indices The index-vector. */ Indices( const std::vector & indices) : _useIndices(true), _indices(&indices), _numberCorrespondences(indices.size()) {} /** * \brief Constructor without index-vector (uses all correspondences). * \param[in] numberCorrespondences The number of correspondences. */ Indices(size_t numberCorrespondences) : _useIndices(false), _numberCorrespondences(numberCorrespondences) {} /** * \brief Get the number of correspondences. * \return The number of correspondences. */ size_t size() const { return _numberCorrespondences; } /** * \brief Get an index. * \param[in] i The index. * \return The index (either directly or from the index-vector). */ int operator[](int i) const { if( _useIndices ) return (*_indices)[i]; return i; } }; } #endif /* OPENGV_INDICES_HPP_ */ opengv/include/opengv/relative_pose/0000775016516101651610000000000013344612246016571 5ustar dimadimaopengv/include/opengv/relative_pose/modules/0000775016516101651610000000000013344612246020241 5ustar dimadimaopengv/include/opengv/relative_pose/modules/sixpt/0000775016516101651610000000000013344612246021410 5ustar dimadimaopengv/include/opengv/relative_pose/modules/sixpt/modules.hpp0000664016516101651610000000666513344612246023606 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_SIXPT_MODULES_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_SIXPT_MODULES_HPP_ #define EQS 60 #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { namespace sixpt { //my solver void fillRow1( const Eigen::Matrix & l01, const Eigen::Matrix & l02, const Eigen::Matrix & l11, const Eigen::Matrix & l12, std::vector & c0, std::vector & c1, std::vector & c2 ); void fillRow2( Eigen::Matrix & M1, int row, const std::vector (&m0)[3], const std::vector (&m1)[3], const std::vector (&m2)[3] ); void setupAction( const std::vector,Eigen::aligned_allocator< Eigen::Matrix > > & L1, const std::vector,Eigen::aligned_allocator< Eigen::Matrix > > & L2, Eigen::Matrix & Action ); } } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_FIVEPT_STEWENIUS_MODULES_HPP_ */ opengv/include/opengv/relative_pose/modules/fivept_nister/0000775016516101651610000000000013344612246023122 5ustar dimadimaopengv/include/opengv/relative_pose/modules/fivept_nister/modules.hpp0000664016516101651610000000712613344612246025311 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_FIVEPT_NISTER_MODULES_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_FIVEPT_NISTER_MODULES_HPP_ #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { namespace fivept_nister { void composeA( const Eigen::Matrix & EE, Eigen::Matrix & A); double polyVal(const Eigen::MatrixXd & p, double x); void computeSeventhOrderPolynomial( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ); void computeSixthOrderPolynomial( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ); void computeTenthOrderPolynomialFrom73( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ); void computeTenthOrderPolynomialFrom64( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ); void pollishCoefficients( const Eigen::Matrix & A, double & x, double & y, double & z); } } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_FIVEPT_NISTER_MODULES_HPP_ */ opengv/include/opengv/relative_pose/modules/eigensolver/0000775016516101651610000000000013344612246022563 5ustar dimadimaopengv/include/opengv/relative_pose/modules/eigensolver/modules.hpp0000664016516101651610000000754013344612246024752 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_EIGENSOLVER_MODULES_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_EIGENSOLVER_MODULES_HPP_ #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { namespace eigensolver { double getSmallestEV( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley, Eigen::Matrix3d & M ); double getSmallestEVwithJacobian( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley, Eigen::Matrix & jacobian); Eigen::Matrix3d composeM( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley); Eigen::Matrix3d composeMwithJacobians( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley, Eigen::Matrix3d & M_jac1, Eigen::Matrix3d & M_jac2, Eigen::Matrix3d & M_jac3 ); } } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_EIGENSOLVER_MODULES_HPP_ */ opengv/include/opengv/relative_pose/modules/fivept_stewenius/0000775016516101651610000000000013344612246023644 5ustar dimadimaopengv/include/opengv/relative_pose/modules/fivept_stewenius/modules.hpp0000664016516101651610000000545313344612246026034 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_FIVEPT_STEWENIUS_MODULES_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_FIVEPT_STEWENIUS_MODULES_HPP_ #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { namespace fivept_stewenius { void composeA( const Eigen::Matrix & EE, Eigen::Matrix & A); } } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_FIVEPT_STEWENIUS_MODULES_HPP_ */ opengv/include/opengv/relative_pose/modules/fivept_kneip/0000775016516101651610000000000013344612246022724 5ustar dimadimaopengv/include/opengv/relative_pose/modules/fivept_kneip/modules.hpp0000664016516101651610000002704413344612246025114 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_FIVEPT_KNEIP_MODULES_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_FIVEPT_KNEIP_MODULES_HPP_ #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { namespace fivept_kneip { Eigen::Matrix initEpncpRowR( std::vector > & c123_1, std::vector > & c123_2); void initMatrix( Eigen::Matrix & groebnerMatrix ); void computeBasis( Eigen::Matrix & groebnerMatrix ); void sPolynomial30( Eigen::Matrix & groebnerMatrix ); void sPolynomial31( Eigen::Matrix & groebnerMatrix ); void groebnerRow30_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial32( Eigen::Matrix & groebnerMatrix ); void groebnerRow31_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial33( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial34( Eigen::Matrix & groebnerMatrix ); void groebnerRow33_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial35( Eigen::Matrix & groebnerMatrix ); void groebnerRow34_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial36( Eigen::Matrix & groebnerMatrix ); void groebnerRow35_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial37( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial38( Eigen::Matrix & groebnerMatrix ); void groebnerRow37_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial39( Eigen::Matrix & groebnerMatrix ); void groebnerRow38_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial40( Eigen::Matrix & groebnerMatrix ); void groebnerRow38_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial41( Eigen::Matrix & groebnerMatrix ); void groebnerRow40_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow34_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow35_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow36_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial42( Eigen::Matrix & groebnerMatrix ); void groebnerRow41_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow32_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial43( Eigen::Matrix & groebnerMatrix ); void groebnerRow42_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial44( Eigen::Matrix & groebnerMatrix ); void groebnerRow43_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow31_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial45( Eigen::Matrix & groebnerMatrix ); void groebnerRow44_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial46( Eigen::Matrix & groebnerMatrix ); void groebnerRow45_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial47( Eigen::Matrix & groebnerMatrix ); void groebnerRow46_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial48( Eigen::Matrix & groebnerMatrix ); void groebnerRow47_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial49( Eigen::Matrix & groebnerMatrix ); void groebnerRow48_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial50( Eigen::Matrix & groebnerMatrix ); void groebnerRow49_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial51( Eigen::Matrix & groebnerMatrix ); void groebnerRow50_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial52( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow51_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial53( Eigen::Matrix & groebnerMatrix ); void groebnerRow52_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial54( Eigen::Matrix & groebnerMatrix ); void groebnerRow30_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow31_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow53_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial55( Eigen::Matrix & groebnerMatrix ); void groebnerRow39_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow54_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial56( Eigen::Matrix & groebnerMatrix ); void groebnerRow38_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow55_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial57( Eigen::Matrix & groebnerMatrix ); void groebnerRow37_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow56_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial58( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow57_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial59( Eigen::Matrix & groebnerMatrix ); void groebnerRow35_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow58_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial60( Eigen::Matrix & groebnerMatrix ); void groebnerRow34_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow59_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial61( Eigen::Matrix & groebnerMatrix ); void groebnerRow33_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow60_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial62( Eigen::Matrix & groebnerMatrix ); void groebnerRow61_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow61_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow61_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial63( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow62_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow62_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow62_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial64( Eigen::Matrix & groebnerMatrix ); void groebnerRow63_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow63_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial65( Eigen::Matrix & groebnerMatrix ); void groebnerRow63_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow64_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow64_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow64_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_FIVEPT_KNEIP_MODULES_HPP_ */ opengv/include/opengv/relative_pose/modules/main.hpp0000664016516101651610000001236413344612246021704 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_MAIN_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_MAIN_HPP_ #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { void fivept_stewenius_main( const Eigen::Matrix & EE, complexEssentials_t & complexEssentials ); void fivept_nister_main( const Eigen::Matrix & EE, essentials_t & essentials ); void fivept_kneip_main( const Eigen::Matrix & f1, const Eigen::Matrix & f2, rotations_t & rotations ); void eigensolver_main( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, eigensolverOutput_t & output ); void sixpt_main( Eigen::Matrix & L1, Eigen::Matrix & L2, rotations_t & solutions); void ge_main( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & startingPoint, geOutput_t & output ); void ge_main2( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & startingPoint, geOutput_t & output ); void ge_plot( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, geOutput_t & output ); } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_MAIN_HPP_ */ opengv/include/opengv/relative_pose/modules/ge/0000775016516101651610000000000013344612246020634 5ustar dimadimaopengv/include/opengv/relative_pose/modules/ge/modules.hpp0000664016516101651610000001527013344612246023022 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_RELATIVE_POSE_MODULES_GE_MODULES_HPP_ #define OPENGV_RELATIVE_POSE_MODULES_GE_MODULES_HPP_ #include #include #include #include namespace opengv { namespace relative_pose { namespace modules { namespace ge { void getEV( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, Eigen::Vector4d & roots ); double getCost( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, int step ); double getCostWithJacobian( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, Eigen::Matrix & jacobian, int step ); void getQuickJacobian( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, double currentValue, Eigen::Matrix & jacobian, int step ); Eigen::Matrix4d composeG( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley); Eigen::Matrix4d composeGwithJacobians( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, Eigen::Matrix4d & G_jac1, Eigen::Matrix4d & G_jac2, Eigen::Matrix4d & G_jac3 ); } } } } #endif /* OPENGV_RELATIVE_POSE_MODULES_GE_MODULES_HPP_ */ opengv/include/opengv/relative_pose/RelativeMultiAdapterBase.hpp0000664016516101651610000002307513344612246024173 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file RelativeMultiAdapterBase.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * relative-pose algorithms. Intended for multi-central-viewpoint or * relative non-central-viewpoint problems. Access of correspondences * etc. via an additional pair-index referring to the pairs of cameras. */ #ifndef OPENGV_RELATIVE_POSE_RELATIVEMULTIADAPTERBASE_HPP_ #define OPENGV_RELATIVE_POSE_RELATIVEMULTIADAPTERBASE_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * See the documentation of RelativeAdapterBase to understand the meaning of * a RelativeAdapter. RelativeMultiAdapterBase extends the interface of * RelativeAdapterBase by an additional pair-index for referring to pairs * of cameras. Intended for special central multi-viewpoint or non-central * relative viewpoint problems, allowing "camera-pair"-wise grouping of * correspondences. Derived classes need to implement functionalities for * deriving unique serialization of multi-indices. */ class RelativeMultiAdapterBase : public RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** See parent-class */ RelativeMultiAdapterBase() : RelativeAdapterBase() {}; /** See parent-class */ RelativeMultiAdapterBase( const rotation_t & R12 ) : RelativeAdapterBase( R12 ) {}; /** See parent-class */ RelativeMultiAdapterBase( const translation_t & t12, const rotation_t & R12 ) : RelativeAdapterBase( t12, R12 ) {}; /** See parent-class */ virtual ~RelativeMultiAdapterBase() {}; //camera-pair-wise access of correspondences /** * \brief Retrieve the bearing vector of a correspondence in camera 1 of a pair. * \param[in] pairIndex Index of the camera-pair. * \param[in] correspondenceIndex Index of the correspondence in the camera-pair. * \return The corresponding bearing vector. */ virtual bearingVector_t getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const = 0; /** * \brief Retrieve the bearing vector of a correspondence in camera 2 of a pair. * \param[in] pairIndex Index of the camera-pair. * \param[in] correspondenceIndex Index of the correspondence in the camera-pair. * \return The corresponding bearing vector. */ virtual bearingVector_t getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const = 0; /** * \brief Retrieve the weight of a correspondence. The weight is supposed to * reflect the quality of a correspondence, and typically is between * 0 and 1. * \param[in] pairIndex Index of the camera-pair. * \param[in] correspondenceIndex Index of the correspondence in the camera-pair. * \return The corresponding weight. */ virtual double getWeight( size_t pairIndex, size_t correspondenceIndex ) const = 0; /** * \brief Retrieve the position of the cameras of a camera-pair seen from the * origin of the viewpoints (assumed to be the same in both * viewpoints). * \param[in] pairIndex Index of the camera-pair. * \return The position of the camera seen from the viewpoint origin. */ virtual translation_t getCamOffset( size_t pairIndex ) const = 0; /** * \brief Retrieve the rotation from the cameras of a camera-pair back to the * origin of the viewpoints (assumed to be the same in both * viewpoints). * \param[in] pairIndex Index of the camera-pair. * \return The rotation from the camera back to the viewpoint origin. */ virtual rotation_t getCamRotation( size_t pairIndex ) const = 0; /** * \brief Retrieve the number of correspondences for a camera-pair. * \param[in] pairIndex Index of the camera-pair. * \return The number of correspondences in this camera-pair. */ virtual size_t getNumberCorrespondences( size_t pairIndex ) const = 0; /** * \brief Retrieve the number of camera-pairs. * \return The number of camera-pairs. */ virtual size_t getNumberPairs() const = 0; //Conversion to and from serialized indices /** * \brief Convert an array of (pairIndex,correspondenceIndex)-pairs into an * array of serialized indices. * \param[in] multiIndices Array of (pairIndex,correspondenceIndex)-pairs. * \return Array of single serialized indices referring uniquely to * (pairIndex,correspondenceIndex)-pairs. */ virtual std::vector convertMultiIndices( const std::vector > & multiIndices ) const = 0; /** * \brief Convert a (pairIndex,correspondenceIndex)-pair into a serialized index. * \param[in] pairIndex The index of the camera-pair. * \param[in] correspondenceIndex The index of the keypoint in the camera-pair. * \return Array of single serialized indices referring uniquely to * (pairIndex,correspondenceIndex)-pairs. */ virtual int convertMultiIndex( size_t pairIndex, size_t correspondenceIndex ) const = 0; /** * \brief Get the camera-pair-index corresponding to a serialized index. * \param[in] index The serialized index. * \return The camera-pair index. */ virtual int multiPairIndex( size_t index ) const = 0; /** * \brief Get the keypoint-index in a camera-pair for a serialized index. * \param[in] index The serialized index. * \return The keyopint-index in the camera-pair. */ virtual int multiCorrespondenceIndex( size_t index ) const = 0; //the classic interface (with serialized indices, used by the opengv-methods) /** See parent-class (no need to overload) */ virtual bearingVector_t getBearingVector1( size_t index ) const { return getBearingVector1( multiPairIndex(index), multiCorrespondenceIndex(index) ); } /** See parent-class (no need to overload) */ virtual bearingVector_t getBearingVector2( size_t index ) const { return getBearingVector2( multiPairIndex(index), multiCorrespondenceIndex(index) ); } /** See parent-class (no need to overload) */ virtual double getWeight( size_t index ) const { return getWeight( multiPairIndex(index), multiCorrespondenceIndex(index) ); } /** See parent-class (no need to overload) */ virtual translation_t getCamOffset1( size_t index ) const { return getCamOffset( multiPairIndex(index) ); } /** See parent-class (no need to overload) */ virtual rotation_t getCamRotation1( size_t index ) const { return getCamRotation( multiPairIndex(index) ); } /** See parent-class (no need to overload) */ virtual translation_t getCamOffset2( size_t index ) const { return getCamOffset( multiPairIndex(index) ); } /** See parent-class (no need to overload) */ virtual rotation_t getCamRotation2( size_t index ) const { return getCamRotation( multiPairIndex(index) ); } /** See parent-class (no need to overload) */ virtual size_t getNumberCorrespondences() const { size_t numberCorrespondences = 0; for(size_t i = 0; i < getNumberPairs(); i++) numberCorrespondences += getNumberCorrespondences(i); return numberCorrespondences; } }; } } #endif /* OPENGV_RELATIVE_POSE_RELATIVEMULTIADAPTERBASE_HPP_ */ opengv/include/opengv/relative_pose/CentralRelativeMultiAdapter.hpp0000664016516101651610000001357613344612246024716 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file CentralRelativeMultiAdapter.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * central relative-pose algorithms. Maps opengv types * back to opengv types. For multi-central-viewpoint. Manages multiple * match-lists for pairs of cameras (e.g. pairs of central viewpoints). */ #ifndef OPENGV_RELATIVE_POSE_CENTRALRELATIVEMULTIADAPTER_HPP_ #define OPENGV_RELATIVE_POSE_CENTRALRELATIVEMULTIADAPTER_HPP_ #include #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeMultiAdapter. This child-class is for the multi-central case and * holds data in form of references to opengv-types. It is meant to be used for * problems involving more than two central viewpoints. This is experimental! */ class CentralRelativeMultiAdapter : public RelativeMultiAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeMultiAdapter( std::vector > bearingVectors1, std::vector > bearingVectors2 ); /** * \brief Destructor. */ virtual ~CentralRelativeMultiAdapter(); //camera-pair-wise access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual double getWeight( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual translation_t getCamOffset( size_t pairIndex ) const; /** See parent-class */ virtual rotation_t getCamRotation( size_t pairIndex ) const; /** See parent-class */ virtual size_t getNumberCorrespondences( size_t pairIndex ) const; /** See parent-class */ virtual size_t getNumberPairs() const; //Conversion to and from serialized indices /** See parent-class */ virtual std::vector convertMultiIndices( const std::vector > & multiIndices ) const; /** See parent-class */ virtual int convertMultiIndex( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual int multiPairIndex( size_t index ) const; /** See parent-class */ virtual int multiCorrespondenceIndex( size_t index ) const; protected: /** References to multiple sets of bearing-vectors (the ones from camera 1 of * each pair, and expressed in there */ std::vector > _bearingVectors1; /** References to multiple sets of bearing-vectors (the ones from camera 1 of * each pair, and expressed in there). */ std::vector > _bearingVectors2; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiPairIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiKeypointIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector singleIndexOffsets; }; } } #endif /* OPENGV_RELATIVE_POSE_CENTRALRELATIVEMULTIADAPTER_HPP_ */ opengv/include/opengv/relative_pose/MANoncentralRelativeMulti.hpp0000664016516101651610000001377713344612246024351 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MANoncentralRelativeMulti.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * non-central relative-pose algorithms. Maps Matlab types * to opengv types. Manages multiple match-lists for pairs of cameras. * This allows to draw samples homogeneously over the cameras. */ #ifndef OPENGV_RELATIVE_POSE_MANONCENTRALRELATIVEMULTI_HPP_ #define OPENGV_RELATIVE_POSE_MANONCENTRALRELATIVEMULTI_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeMultiAdapter. This child-class is for the relative non-central case * and holds data in form of pointers to matlab-types. It is meant to be used * for problems involving two non-central viewpoints, but in the special case * where correspondences result from two cameras with equal transformation * to their two viewpoints. */ class MANoncentralRelativeMulti : public RelativeMultiAdapterBase { protected: using RelativeMultiAdapterBase::_t12; using RelativeMultiAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ MANoncentralRelativeMulti( const std::vector & bearingVectors1, const std::vector & bearingVectors2, const double * camOffsets, const std::vector & numberBearingVectors ); /** * \brief Destructor. */ virtual ~MANoncentralRelativeMulti(); //camera-pair-wise access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual double getWeight( size_t camIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual translation_t getCamOffset( size_t pairIndex ) const; /** See parent-class */ virtual rotation_t getCamRotation( size_t pairIndex ) const; /** See parent-class */ virtual size_t getNumberCorrespondences( size_t pairIndex ) const; /** See parent-class */ virtual size_t getNumberPairs() const; //Conversion to and from serialized indices /** See parent-class */ virtual std::vector convertMultiIndices( const std::vector > & multiIndices ) const; /** See parent-class */ virtual int convertMultiIndex( size_t camIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual int multiPairIndex( size_t index ) const; /** See parent-class */ virtual int multiCorrespondenceIndex( size_t index ) const; protected: /** A pointer to the bearing-vectors in viewpoint 1 */ std::vector _bearingVectors1; /** A pointer to the bearing-vectors in viewpoint 2 */ std::vector _bearingVectors2; /** The offset from the viewpoint origin of each vector */ const double * _camOffsets; /** The number of bearing-vectors in each camera */ std::vector _numberBearingVectors; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiPairIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiKeypointIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector singleIndexOffsets; }; } } #endif /* OPENGV_RELATIVE_POSE_MANONCENTRALRELATIVEMULTI_HPP_ */ opengv/include/opengv/relative_pose/NoncentralRelativeAdapter.hpp0000664016516101651610000001530313344612246024404 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file NoncentralRelativeAdapter.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * non-central relative-pose algorithms. Maps opengv types * back to opengv types. */ #ifndef OPENGV_RELATIVE_POSE_NONCENTRALRELATIVEADAPTER_HPP_ #define OPENGV_RELATIVE_POSE_NONCENTRALRELATIVEADAPTER_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeAdapter. This child-class is for the non-central case and holds * data in form of references to opengv-types. */ class NoncentralRelativeAdapter : public RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** A type defined for the camera-correspondences, see protected * class-members */ typedef std::vector camCorrespondences_t; /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const camCorrespondences_t & camCorrespondences1, const camCorrespondences_t & camCorrespondences2, const translations_t & camOffsets, const rotations_t & camRotations ); /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const camCorrespondences_t & camCorrespondences1, const camCorrespondences_t & camCorrespondences2, const translations_t & camOffsets, const rotations_t & camRotations, const rotation_t & R12 ); /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const camCorrespondences_t & camCorrespondences1, const camCorrespondences_t & camCorrespondences2, const translations_t & camOffsets, const rotations_t & camRotations, const translation_t & t12, const rotation_t & R12 ); /** * \brief Destructor. */ virtual ~NoncentralRelativeAdapter(); //Access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t index ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class */ virtual translation_t getCamOffset1( size_t index ) const; /** See parent-class */ virtual rotation_t getCamRotation1( size_t index ) const; /** See parent-class */ virtual translation_t getCamOffset2( size_t index ) const; /** See parent-class */ virtual rotation_t getCamRotation2( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** Reference to bearing-vectors in viewpoint 1. * (expressed in their individual cameras) */ const bearingVectors_t & _bearingVectors1; /** Reference to bearing-vectors in viewpoint 2. * (expressed in their individual cameras) */ const bearingVectors_t & _bearingVectors2; /** Reference to an array of camera-indices for the bearing vectors in * viewpoint 1. Length equals to number of bearing-vectors in viewpoint 1, * and elements are indices of cameras in the _camOffsets and _camRotations * arrays. */ const camCorrespondences_t & _camCorrespondences1; /** Reference to an array of camera-indices for the bearing vectors in * viewpoint 2. Length equals to number of bearing-vectors in viewpoint 2, * and elements are indices of cameras in the _camOffsets and _camRotations * arrays. */ const camCorrespondences_t & _camCorrespondences2; /** Reference to positions of the different cameras seen from their * viewpoint. */ const translations_t & _camOffsets; /** Reference to rotations from the different cameras back to their * viewpoint. */ const rotations_t & _camRotations; }; } } #endif /* OPENGV_RELATIVE_POSE_NONCENTRALRELATIVEADAPTER_HPP_ */ opengv/include/opengv/relative_pose/CentralRelativeWeightingAdapter.hpp0000664016516101651610000001322413344612246025537 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file CentralRelativeWeightingAdapter.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * central relative-pose algorithms. Maps opengv types back to * opengv types. Also contains "weights" reflecting the quality of * a feature correspondence (typically between 0 and 1) */ #ifndef OPENGV_RELATIVE_POSE_CENTRALRELATIVEWEIGHTINGADAPTER_HPP_ #define OPENGV_RELATIVE_POSE_CENTRALRELATIVEWEIGHTINGADAPTER_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeAdapter. This child-class is for the central case and holds data * in form of references to opengv-types. It also includes weights for the * correspondences. */ class CentralRelativeWeightingAdapter : public RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeWeightingAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const std::vector & weights ); /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeWeightingAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const std::vector & weights, const rotation_t & R12 ); /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeWeightingAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const std::vector & weights, const translation_t & t12, const rotation_t & R12 ); /** * \brief Destructor. */ virtual ~CentralRelativeWeightingAdapter(); //Access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t index ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual translation_t getCamOffset1( size_t index ) const; /** See parent-class. Returns identity for this adapter. */ virtual rotation_t getCamRotation1( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual translation_t getCamOffset2( size_t index ) const; /** See parent-class. Returns identity for this adapter. */ virtual rotation_t getCamRotation2( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** Reference to bearing-vectors expressed in viewpoint 1. */ const bearingVectors_t & _bearingVectors1; /** Reference to bearing-vectors expressed in viewpoint 2. */ const bearingVectors_t & _bearingVectors2; /** Reference to an array of weights. Indexing follows _bearingVectors2. */ const std::vector & _weights; }; } } #endif /* OPENGV_RELATIVE_POSE_CENTRALRELATIVEWEIGHTINGADAPTER_HPP_ */ opengv/include/opengv/relative_pose/RelativeAdapterBase.hpp0000664016516101651610000001753613344612246023165 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file RelativeAdapterBase.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * relative-pose algorithms. */ #ifndef OPENGV_RELATIVE_POSE_RELATIVEADAPTERBASE_HPP_ #define OPENGV_RELATIVE_POSE_RELATIVEADAPTERBASE_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * The RelativeAdapterBase is the base-class for the visitors to the central * and non-central relative pose algorithms. It provides a unified interface to * opengv-methods to access bearing-vector correspondences, priors or known * variables for the relative pose, and the multi-camera configuration in the * non-central case. Derived classes may hold the data in any user-specific * format, and adapt to opengv-types. */ class RelativeAdapterBase { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. */ RelativeAdapterBase( ) : _t12(Eigen::Vector3d::Zero()), _R12(Eigen::Matrix3d::Identity()) {}; /** * \brief Constructor. * \param[in] R12 A prior or known value for the rotation from viewpoint 2 * to viewpoint 1. */ RelativeAdapterBase( const rotation_t & R12 ) : _t12(Eigen::Vector3d::Zero()), _R12(R12) {}; /** * \brief Constructor. * \param[in] t12 A prior or known value for the position of viewpoint 2 seen * from viewpoint 1. * \param[in] R12 A prior or known value for the rotation from viewpoint 2 * to viewpoint 1. */ RelativeAdapterBase( const translation_t & t12, const rotation_t & R12 ) : _t12(t12), _R12(R12) {}; /** * \brief Destructor. */ virtual ~RelativeAdapterBase() {}; //Access of correspondences /** * \brief Retrieve the bearing vector of a correspondence in viewpoint 1. * \param[in] index The serialized index of the correspondence. * \return The corresponding bearing vector. */ virtual opengv::bearingVector_t getBearingVector1( size_t index ) const = 0; /** * \brief Retrieve the bearing vector of a correspondence in viewpoint 2. * \param[in] index The serialized index of the correspondence. * \return The corresponding bearing vector. */ virtual opengv::bearingVector_t getBearingVector2( size_t index ) const = 0; /** * \brief Retrieve the weight of a correspondence. The weight is supposed to * reflect the quality of a correspondence, and typically is between * 0 and 1. * \param[in] index The serialized index of the correspondence. * \return The corresponding weight. */ virtual double getWeight( size_t index ) const = 0; /** * \brief Retrieve the position of a camera of a correspondence in viewpoint * 1 seen from the origin of the viewpoint. * \param[in] index The serialized index of the correspondence. * \return The position of the corresponding camera seen from the viewpoint * origin. */ virtual opengv::translation_t getCamOffset1( size_t index ) const = 0; /** * \brief Retrieve the rotation from a camera of a correspondence in * viewpoint 1 to the viewpoint origin. * \param[in] index The serialized index of the correspondence. * \return The rotation from the corresponding camera back to the viewpoint * origin. */ virtual opengv::rotation_t getCamRotation1( size_t index ) const = 0; /** * \brief Retrieve the position of a camera of a correspondence in viewpoint * 2 seen from the origin of the viewpoint. * \param[in] index The serialized index of the correspondence. * \return The position of the corresponding camera seen from the viewpoint * origin. */ virtual opengv::translation_t getCamOffset2( size_t index ) const = 0; /** * \brief Retrieve the rotation from a camera of a correspondence in * viewpoint 2 to the viewpoint origin. * \param[in] index The serialized index of the correspondence. * \return The rotation from the corresponding camera back to the viewpoint * origin. */ virtual opengv::rotation_t getCamRotation2( size_t index ) const = 0; /** * \brief Retrieve the number of correspondences. * \return The number of correspondences. */ virtual size_t getNumberCorrespondences() const = 0; //Access of priors or known values /** * \brief Retrieve the prior or known value for the relative position. * \return The prior or known value for the position. */ opengv::translation_t gett12() const { return _t12; }; /** * \brief Set the prior or known value for the relative position. * \param[in] t12 The prior or known value for the position. */ void sett12(const opengv::translation_t & t12) { _t12 = t12; }; /** * \brief Retrieve the prior or known value for the relative rotation. * \return The prior or known value for the rotation. */ opengv::rotation_t getR12() const { return _R12; }; /** * \brief Set the prior or known value for the relative rotation. * \param[in] R12 The prior or known value for the rotation. */ void setR12(const opengv::rotation_t & R12) { _R12 = R12; }; protected: /** Prior or known value for the position of viewpoint 2 seen from * viewpoint 1. Initialized to zero if not provided. */ opengv::translation_t _t12; /** Prior or known value for the rotation from viewpoint 2 back to * viewpoint 1. Initialized to identity if not provided. */ opengv::rotation_t _R12; }; } } #endif /* OPENGV_RELATIVE_POSE_RELATIVEADAPTERBASE_HPP_ */ opengv/include/opengv/relative_pose/MANoncentralRelative.hpp0000664016516101651610000001127513344612246023325 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MANoncentralRelative.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * non-central relative-pose algorithms. Maps matlab types * to opengv types. */ #ifndef OPENGV_RELATIVE_POSE_MANONCENTRALRELATIVE_HPP_ #define OPENGV_RELATIVE_POSE_MANONCENTRALRELATIVE_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeAdapter. This child-class is for the non-central case and holds * data in form of pointers to matlab-types. */ class MANoncentralRelative : public RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ MANoncentralRelative( const double * bearingVectors1, const double * bearingVectors2, int numberBearingVectors1, int numberBearingVectors2 ); /** * \brief Destructor. */ virtual ~MANoncentralRelative(); //Access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t index ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class */ virtual translation_t getCamOffset1( size_t index ) const; /** See parent-class */ virtual rotation_t getCamRotation1( size_t index ) const; /** See parent-class */ virtual translation_t getCamOffset2( size_t index ) const; /** See parent-class */ virtual rotation_t getCamRotation2( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** A pointer to the bearing-vectors in viewpoint 1 */ const double * _bearingVectors1; /** A pointer to the bearing-vectors in viewpoint 2 */ const double * _bearingVectors2; /** The number of bearing-vectors in viewpoint 1 */ int _numberBearingVectors1; /** The number of bearing-vectors in viewpoint 2 */ int _numberBearingVectors2; }; } } #endif /* OPENGV_RELATIVE_POSE_MANONCENTRALRELATIVE_HPP_ */ opengv/include/opengv/relative_pose/NoncentralRelativeMultiAdapter.hpp0000664016516101651610000001453413344612246025424 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file NoncentralRelativeMultiAdapter.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * non-central relative-pose algorithms. Maps opengv types * back to opengv types. Manages multiple match-lists for pairs of cameras. * This allows to draw samples homogeneously over the cameras. */ #ifndef OPENGV_RELATIVE_POSE_NONCENTRALRELATIVEMULTIADAPTER_HPP_ #define OPENGV_RELATIVE_POSE_NONCENTRALRELATIVEMULTIADAPTER_HPP_ #include #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeMultiAdapter. This child-class is for the relative non-central case * and holds data in form of references to opengv-types. It is meant to be used * for problems involving two non-central viewpoints, but in the special case * where correspondences result from two cameras with equal transformation * to their two viewpoints. */ class NoncentralRelativeMultiAdapter : public RelativeMultiAdapterBase { protected: using RelativeMultiAdapterBase::_t12; using RelativeMultiAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralRelativeMultiAdapter( std::vector > bearingVectors1, std::vector > bearingVectors2, const translations_t & camOffsets, const rotations_t & camRotations ); /** * \brief Destructor. */ virtual ~NoncentralRelativeMultiAdapter(); //camera-pair-wise access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual double getWeight( size_t camIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual translation_t getCamOffset( size_t pairIndex ) const; /** See parent-class */ virtual rotation_t getCamRotation( size_t pairIndex ) const; /** See parent-class */ virtual size_t getNumberCorrespondences( size_t pairIndex ) const; /** See parent-class */ virtual size_t getNumberPairs() const; //Conversion to and from serialized indices /** See parent-class */ virtual std::vector convertMultiIndices( const std::vector > & multiIndices ) const; /** See parent-class */ virtual int convertMultiIndex( size_t camIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual int multiPairIndex( size_t index ) const; /** See parent-class */ virtual int multiCorrespondenceIndex( size_t index ) const; protected: /** References to multiple sets of bearing-vectors (the ones from camera 1 of * each pair, and expressed in there). */ std::vector > _bearingVectors1; /** References to multiple sets of bearing-vectors (the ones from camera 2 of * each pair, and expressed in there). */ std::vector > _bearingVectors2; /** Reference to positions of the different cameras seen from the * viewpoints. */ const translations_t & _camOffsets; /** Reference to rotations from the different cameras back to the * viewpoints. */ const rotations_t & _camRotations; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiPairIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiKeypointIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector singleIndexOffsets; }; } } #endif /* OPENGV_RELATIVE_POSE_NONCENTRALRELATIVEMULTIADAPTER_HPP_ */ opengv/include/opengv/relative_pose/MACentralRelative.hpp0000664016516101651610000001143513344612246022610 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MACentralRelative.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * central relative-pose algorithms. Maps matlab types to opengv types. */ #ifndef OPENGV_RELATIVE_POSE_MACENTRALRELATIVE_HPP_ #define OPENGV_RELATIVE_POSE_MACENTRALRELATIVE_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeAdapter. This child-class is for the central case and holds data * in form of pointers to matlab data. */ class MACentralRelative : public RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ MACentralRelative( const double * bearingVectors1, const double * bearingVectors2, int numberBearingVectors1, int numberBearingVectors2 ); /** * \brief Destructor. */ virtual ~MACentralRelative(); //Access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t index ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual translation_t getCamOffset1( size_t index ) const; /** See parent-class. Returns identity for this adapter. */ virtual rotation_t getCamRotation1( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual translation_t getCamOffset2( size_t index ) const; /** See parent-class. Returns identity for this adapter. */ virtual rotation_t getCamRotation2( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** A pointer to the bearing-vectors in viewpoint 1 */ const double * _bearingVectors1; /** A pointer to the bearing-vectors in viewpoint 2 */ const double * _bearingVectors2; /** The number of bearing-vectors in viewpoint 1 */ int _numberBearingVectors1; /** The number of bearing-vectors in viewpoint 2 */ int _numberBearingVectors2; }; } } #endif /* OPENGV_RELATIVE_POSE_MACENTRALRELATIVE_HPP_ */ opengv/include/opengv/relative_pose/methods.hpp0000664016516101651610000005365313344612246020761 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file relative_pose/methods.hpp * \brief A collection of methods for computing the relative pose between two * calibrated central or non-central viewpoints. */ #ifndef OPENGV_RELATIVE_POSE_METHODS_HPP_ #define OPENGV_RELATIVE_POSE_METHODS_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * \brief Compute the translation between two central viewpoints with known * relative rotation, and using two correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences and known * relative rotation. * \param[in] unrotate Set to true if known rotation should be used to * unrotate bearing vectors from viewpoint 2 (not required * in case of identity rotation). * \param[in] indices Indices of the two correspondences used for deriving the * translation. * \return Position of viewpoint 2 seen from viewpoint 1. */ translation_t twopt( const RelativeAdapterBase & adapter, bool unrotate, const std::vector & indices ); /** * \brief Compute the translation between two central viewpoints with known * relative rotation, and using two correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences and known * relative rotation. * \param[in] unrotate Set to true if known rotation should be used to * unrotate bearing vectors from viewpoint 2 (not required * in case of identity rotation). * \param[in] index0 Index of the first correspondence used for deriving the * translation (use default value if only two provided * anyway). * \param[in] index1 Index of the second correspondence used for deriving the * translation (use default vector if only two provided * anyway). * \return Position of viewpoint 2 seen from viewpoint 1. */ translation_t twopt( const RelativeAdapterBase & adapter, bool unrotate, size_t index0 = 0, size_t index1 = 1 ); /** * \brief Compute the rotation between two central viewpoints with pure * rotation change, using only two correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the two correspondences used for deriving the * rotation. * \return Rotation from viewpoint 2 to viewpoint 1. */ rotation_t twopt_rotationOnly( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the rotation between two central viewpoints with pure * rotation change, using only two correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] index0 Index of the first correspondence used for deriving the * rotation (use default value if only two provided anyway). * \param[in] index1 Index of the second correspondence used for deriving the * rotation (use default value if only two provided anyway). * \return Rotation from viewpoint 2 to viewpoint 1. */ rotation_t twopt_rotationOnly( const RelativeAdapterBase & adapter, size_t index0 = 0, size_t index1 = 1 ); /** * \brief Compute the rotation between two central viewpoints with pure * rotation change using Arun's method [13]. Using all available * correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \return Rotation from viewpoint 2 to viewpoint 1. */ rotation_t rotationOnly( const RelativeAdapterBase & adapter ); /** * \brief Compute the rotation between two central viewpoints with pure * rotation change using Arun's method [13]. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the correspondences used for deriving * the rotation. * \return Rotation from viewpoint 2 to viewpoint 1. */ rotation_t rotationOnly( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the complex essential matrices between two central viewpoints * using Stewenius' method [5]. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \return Complex essential matrices * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1, maximum of 10 solutions). */ complexEssentials_t fivept_stewenius( const RelativeAdapterBase & adapter ); /** * \brief Compute the complex essential matrices between two central viewpoints * using Stewenius' method [5]. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the correspondences used for deriving * the essential matrices. * \return Complex essential matrices * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1, maximum of 10 solutions). */ complexEssentials_t fivept_stewenius( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the essential matrices between two central viewpoints using * Nister's method [6]. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \return Real essential matrices * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1, maximum of 10 solutions). */ essentials_t fivept_nister( const RelativeAdapterBase & adapter ); /** * \brief Compute the essential matrices between two central viewpoints using * Nister's method [6]. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the correspondences used for deriving * the essential matrices. * \return Real essential matrices * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1, maximum of 10 solutions). */ essentials_t fivept_nister( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the rotation matrices between two central viewpoints using * Kneips's method [7]. Only minimal case. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the correspondences used for deriving * the rotation matrices. * \return Rotation matrices from viewpoint 2 to viewpoint 1 * (maximum 20 solutions). */ rotations_t fivept_kneip( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the essential matrices between two central viewpoints using * the seven-point algorithm [8]. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \return Real essential matrices * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1, maximum 3 solutions). */ essentials_t sevenpt( const RelativeAdapterBase & adapter ); /** * \brief Compute the essential matrices between two central viewpoints using * the seven-point algorithm [8]. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the correspondences used for deriving * the essential matrices. * \return Real essential matrices * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1, maximum 3 solutions). */ essentials_t sevenpt( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the essential matrix between two central viewpoints using * the eight-point algorithm [9,10]. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \return Real essential matrix * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1). */ essential_t eightpt( const RelativeAdapterBase & adapter ); /** * \brief Compute the essential matrix between two central viewpoints using * the eight-point algorithm [9,10]. * * \param[in] adapter Visitor holding bearing-vector correspondences. * \param[in] indices Indices of the correspondences used for deriving * the essential matrix. * \return Real essential matrix * (\f$ \mathbf{E}= \f$ skew\f$(\mathbf{t})\mathbf{R}\f$, where * \f$ \mathbf{t} \f$ is the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ is the rotation from viewpoint * 2 back to viewpoint 1). */ essential_t eightpt( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the rotation matrix between two central viewpoints as an * iterative eigenproblem [11]. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * initial rotation for the optimization. * \param[out] output Returns more complete information (position of viewpoint * 2 seen from viewpoint 1, eigenvectors and eigenvalues) * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t eigensolver( const RelativeAdapterBase & adapter, eigensolverOutput_t & output, bool useWeights = false ); /** * \brief Compute the rotation matrix between two central viewpoints as an * iterative eigenproblem [11]. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * initial rotation for the optimization. * \param[in] indices Indices of the correspondences used for deriving * the rotation matrix. * \param[out] output Returns more complete information (position of viewpoint * 2 seen from viewpoint 1, eigenvectors and eigenvalues) * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t eigensolver( const RelativeAdapterBase & adapter, const std::vector & indices, eigensolverOutput_t & output, bool useWeights = false ); /** * \brief Compute the rotation matrix between two central viewpoints as an * iterative eigenproblem [11]. Using all available correspondences. * Outputs only the rotation. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * initial rotation for the optimization. * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t eigensolver( const RelativeAdapterBase & adapter, bool useWeights = false ); /** * \brief Compute the rotation matrix between two central viewpoints as an * iterative eigenproblem [11]. Outputs only the rotation. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * initial rotation for the optimization. * \param[in] indices Indices of the correspondences used for deriving * the rotation matrix. * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t eigensolver( const RelativeAdapterBase & adapter, const std::vector & indices, bool useWeights = false ); /** * \brief Compute the relative rotation between two non-central viewpoints * following Stewenius' method [16]. Assuming exactly 6 correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * multi-camera configuration. * \return Rotations from viewpoint 2 back to viewpoint 1 */ rotations_t sixpt( const RelativeAdapterBase & adapter ); /** * \brief Compute the relative rotation between two non-central viewpoints * following Stewenius' method using 6 correspondences [16]. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * multi-camera configuration. * \param[in] indices Indices of the six correspondences used for deriving * the rotation matrix. * \return Rotations from viewpoint 2 back to viewpoint 1 */ rotations_t sixpt( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the rotation matrix between two non-central viewpoints as an * iterative eigenproblem. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences, the multi- * camera configuration, plus the initial rotation for the * optimization. * \param[out] output Returns more complete information (position of viewpoint * 2 seen from viewpoint 1, eigenvectors and eigenvalues) * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t ge( const RelativeAdapterBase & adapter, geOutput_t & output, bool useWeights = false ); /** * \brief Compute the rotation matrix between two non-central viewpoints as an * iterative eigenproblem. * * \param[in] adapter Visitor holding bearing-vector correspondences, the multi- * camera configuration, plus the initial rotation for the * optimization. * \param[in] indices Indices of the correspondences used for deriving * the rotation matrix. * \param[out] output Returns more complete information (position of viewpoint * 2 seen from viewpoint 1, eigenvectors and eigenvalues) * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t ge( const RelativeAdapterBase & adapter, const std::vector & indices, geOutput_t & output, bool useWeights = false ); /** * \brief Compute the rotation matrix between two non-central viewpoints as an * iterative eigenproblem. Using all available correspondences. * Outputs only the rotation. * * \param[in] adapter Visitor holding bearing-vector correspondences, the multi- * camera configuration, plus the initial rotation for the * optimization. * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t ge( const RelativeAdapterBase & adapter, bool useWeights = false ); /** * \brief Compute the rotation matrix between two non-central viewpoints as an * iterative eigenproblem. Outputs only the rotation. * * \param[in] adapter Visitor holding bearing-vector correspondences, the multi- * camera configuration, plus the initial rotation for the * optimization. * \param[in] indices Indices of the correspondences used for deriving * the rotation matrix. * \param[in] useWeights Use weights to weight the summation terms? * \return Rotation matrix from viewpoint 2 to viewpoint 1. */ rotation_t ge( const RelativeAdapterBase & adapter, const std::vector & indices, bool useWeights = false ); /** * \brief Compute the relative pose between two non-central viewpoints * following Li's method [12]. Using all available correspondences. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * multi-camera configuration. * \return Pose of viewpoint 2 seen from viewpoint 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ being the rotation from * viewpoint 2 to viewpoint 1). */ transformation_t seventeenpt( const RelativeAdapterBase & adapter ); /** * \brief Compute the relative pose between two non-central viewpoints * following Li's method [12]. * * \param[in] adapter Visitor holding bearing-vector correspondences, plus the * multi-camera configuration. * \param[in] indices Indices of the correspondences used for deriving * the rotation matrix. * \return Pose of viewpoint 2 seen from viewpoint 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ being the rotation from * viewpoint 2 to viewpoint 1). */ transformation_t seventeenpt( const RelativeAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose between two viewpoints using nonlinear optimization. * Using all available correspondences. Works for both central and * non-central case. * * \param[in] adapter Visitor holding bearing-vector correspondences, the * multi-camera configuration, plus the initial values. * \return Pose of viewpoint 2 seen from viewpoint 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ being the rotation from * viewpoint 2 to viewpoint 1). */ transformation_t optimize_nonlinear( RelativeAdapterBase & adapter ); /** * \brief Compute the pose between two viewpoints using nonlinear optimization. * Works for both central and non-central case. * * \param[in] adapter Visitor holding bearing-vector correspondences, the * multi-camera configuration, plus the initial values. * \param[in] indices Indices of the correspondences used for deriving the pose. * \return Pose of viewpoint 2 seen from viewpoint 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of viewpoint 2 seen from * viewpoint 1, and \f$ \mathbf{R} \f$ being the rotation from * viewpoint 2 to viewpoint 1). */ transformation_t optimize_nonlinear( RelativeAdapterBase & adapter, const std::vector & indices ); } } #endif /* OPENGV_RELATIVE_POSE_METHODS_HPP_ */ opengv/include/opengv/relative_pose/CentralRelativeAdapter.hpp0000664016516101651610000001224413344612246023672 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file CentralRelativeAdapter.hpp * \brief Adapter-class for passing bearing-vector correspondences to the * central relative-pose algorithms. Maps opengv types back to * opengv types. */ #ifndef OPENGV_RELATIVE_POSE_CENTRALRELATIVEADAPTER_HPP_ #define OPENGV_RELATIVE_POSE_CENTRALRELATIVEADAPTER_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Check the documentation of the parent-class to understand the meaning of * a RelativeAdapter. This child-class is for the central case and holds data * in form of references to opengv-types. */ class CentralRelativeAdapter : public RelativeAdapterBase { protected: using RelativeAdapterBase::_t12; using RelativeAdapterBase::_R12; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2 ); /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const rotation_t & R12 ); /** * \brief Constructor. See protected class-members to understand parameters */ CentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const translation_t & t12, const rotation_t & R12 ); /** * \brief Destructor. */ virtual ~CentralRelativeAdapter(); //Access of correspondences /** See parent-class */ virtual bearingVector_t getBearingVector1( size_t index ) const; /** See parent-class */ virtual bearingVector_t getBearingVector2( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual translation_t getCamOffset1( size_t index ) const; /** See parent-class. Returns identity for this adapter. */ virtual rotation_t getCamRotation1( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual translation_t getCamOffset2( size_t index ) const; /** See parent-class. Returns identity for this adapter. */ virtual rotation_t getCamRotation2( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** Reference to bearing-vectors expressed in viewpoint 1. */ const bearingVectors_t & _bearingVectors1; /** Reference to bearing-vectors expressed in viewpoint 2. */ const bearingVectors_t & _bearingVectors2; }; } } #endif /* OPENGV_RELATIVE_POSE_CENTRALRELATIVEADAPTER_HPP_ */ opengv/include/opengv/math/0000775016516101651610000000000013344612246014661 5ustar dimadimaopengv/include/opengv/math/quaternion.hpp0000664016516101651610000000630013344612246017556 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file quaternion.hpp * \brief Functions for back-and-forth transformation between rotation matrices * and quaternion-parameters. */ #ifndef OPENGV_QUATERNION_HPP_ #define OPENGV_QUATERNION_HPP_ #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace of the math tools. */ namespace math { /** * \brief Compute a rotation matrix from quaternion-parameters. Assumes that the * quaternion has unit norm. * * \param[in] quaternion The quaternion-parameters of a rotation. * \return The 3x3 rotation matrix. */ rotation_t quaternion2rot( const quaternion_t & quaternion); /** * \brief Compute the quaternion-parameters of a rotation matrix. * * \param[in] R The 3x3 rotation matrix. * \return The quaternion-parameters. */ quaternion_t rot2quaternion( const rotation_t & R ); } } #endif /* OPENGV_QUATERNION_HPP_ */ opengv/include/opengv/math/Sturm.hpp0000664016516101651610000001355713344612246016517 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file Sturm.hpp * \brief Class for evaluating Sturm chains on polynomials, and bracketing the * real roots. */ #ifndef OPENGV_STURM_HPP_ #define OPENGV_STURM_HPP_ #include #include #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace of the math tools. */ namespace math { class Bracket { public: typedef std::shared_ptr Ptr; typedef std::shared_ptr ConstPtr; Bracket( double lowerBound, double upperBound ); Bracket( double lowerBound, double upperBound, size_t changes, bool setUpperBoundChanges ); virtual ~Bracket(); bool dividable( double eps ) const; void divide( std::list & brackets ) const; double lowerBound() const; double upperBound() const; bool lowerBoundChangesComputed() const; bool upperBoundChangesComputed() const; void setLowerBoundChanges( size_t changes ); void setUpperBoundChanges( size_t changes ); size_t numberRoots() const; private: double _lowerBound; double _upperBound; bool _lowerBoundChangesComputed; bool _upperBoundChangesComputed; size_t _lowerBoundChanges; size_t _upperBoundChanges; }; /** * Sturm is initialized over polynomials of arbitrary order, and used to compute * the real roots of the polynomial. */ class Sturm { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** A pair of values bracketing a real root */ typedef std::pair bracket_t; /** * \brief Contructor. * \param[in] p The polynomial coefficients (poly = p(0,0)*x^n + p(0,1)*x^(n-1) ...). */ Sturm( const Eigen::MatrixXd & p ); /** * \brief Contructor. * \param[in] p The polynomial coefficients (poly = p[0]*x^n + p[1]*x^(n-1) ...). */ Sturm( const std::vector & p ); /** * \brief Destructor. */ virtual ~Sturm(); void findRoots2( std::vector & roots, double eps_x = 0.001, double eps_val = 0.001 ); /** * \brief Finds the roots of the polynomial. * \return An array with the real roots of the polynomial. */ std::vector findRoots(); /** * \brief Finds brackets for the real roots of the polynomial. * \return A list of brackets for the real roots of the polynomial. */ void bracketRoots( std::vector & roots, double eps = -1.0 ); /** * \brief Evaluates the Sturm chain at a single bound. * \param[in] bound The bound. * \return The number of sign changes on the bound. */ size_t evaluateChain( double bound ); /** * \brief Evaluates the Sturm chain at a single bound. * \param[in] bound The bound. * \return The number of sign changes on the bound. */ size_t evaluateChain2( double bound ); /** * \brief Composes an initial bracket for all the roots of the polynomial. * \return The maximum of the absolute values of the bracket-values (That's * what the Lagrangian bound is able to find). */ double computeLagrangianBound(); private: /** * \brief Internal function used for composing the Sturm chain * \param[in] p1 First polynomial. * \param[in] p2 Second polynomial. * \param[out] r The negated remainder of the polynomial division p1/p2. */ void computeNegatedRemainder( const Eigen::MatrixXd & p1, const Eigen::MatrixXd & p2, Eigen::MatrixXd & r ); /** A matrix containing the coefficients of the Sturm-chain of the polynomial */ Eigen::MatrixXd _C; /** The dimension _C, which corresponds to (polynomial order+1) */ size_t _dimension; }; } } #endif /* OPENGV_STURM_HPP_ */ opengv/include/opengv/math/cayley.hpp0000664016516101651610000000710113344612246016657 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file cayley.hpp * \brief Functions for back-and-forth transformation between rotation matrices * and Cayley-parameters. */ #ifndef OPENGV_CAYLEY_HPP_ #define OPENGV_CAYLEY_HPP_ #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace of the math tools. */ namespace math { /** * \brief Compute a rotation matrix from Cayley-parameters, following [14]. * * \param[in] cayley The Cayley-parameters of a rotation. * \return The 3x3 rotation matrix. */ rotation_t cayley2rot( const cayley_t & cayley); /** * \brief Compute a fake rotation matrix from Cayley-parameters, following [14]. * The rotation matrix is missing the scaling parameter of the * Cayley-transform. This short form is useful for the Jacobian-based * iterative rotation optimization of the eigensolver [11]. * * \param[in] cayley The Cayley-parameters of the rotation. * \return The false 3x3 rotation matrix. */ rotation_t cayley2rot_reduced( const cayley_t & cayley); /** * \brief Compute the Cayley-parameters of a rotation matrix, following [14]. * * \param[in] R The 3x3 rotation matrix. * \return The Cayley-parameters. */ cayley_t rot2cayley( const rotation_t & R ); } } #endif /* OPENGV_CAYLEY_HPP_ */ opengv/include/opengv/math/gauss_jordan.hpp0000664016516101651610000000570213344612246020055 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file gauss_jordan.hpp * \brief Sparse, fast Gauss Jordan elimination. */ #ifndef OPENGV_GAUSS_JORDAN_HPP_ #define OPENGV_GAUSS_JORDAN_HPP_ #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace of the math tools. */ namespace math { /** * \brief Sparse, fast Gauss Jordan elimination on matrices with a left square * invertible block. * * \param[in] matrix The matrix. * \param[in] exitCondition The last row we process when stepping up. */ void gauss_jordan( std::vector*> & matrix, int exitCondition = 0 ); } } #endif /* OPENGV_GAUSS_JORDAN_HPP_ */ opengv/include/opengv/math/arun.hpp0000664016516101651610000000734013344612246016343 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file arun.hpp * \brief Arun's method for computing the rotation between two point sets. */ #ifndef OPENGV_ARUN_HPP_ #define OPENGV_ARUN_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace of the math tools. */ namespace math { /** * \brief Arun's method for computing the rotation between two point sets. * Core function [13]. * * \param[in] Hcross The summation over the exterior products between the * normalized points. * \return The rotation matrix that aligns the points. */ rotation_t arun( const Eigen::MatrixXd & Hcross ); /** * \brief Arun's method for complete point cloud alignment [13]. The method * actually does the same than threept_arun, but has a different * interface. * * \param[in] p1 The points expressed in the first frame. * \param[in] p2 The points expressed in the second frame. * \return The Transformation from frame 2 to frame 1 ( * \f$ \mathbf{T} = \left(\begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array}\right) \f$, * with \f$ \mathbf{t} \f$ being the position of frame 2 seen from * frame 1, and \f$ \mathbf{R} \f$ being the rotation from * frame 2 to frame 1). */ transformation_t arun_complete( const points_t & p1, const points_t & p2 ); } } #endif /* OPENGV_ARUN_HPP_ */ opengv/include/opengv/math/roots.hpp0000664016516101651610000000707613344612246016552 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file roots.hpp * \brief Closed-form solutions for computing the roots of a polynomial. */ #ifndef OPENGV_ROOTS_HPP_ #define OPENGV_ROOTS_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace of the math tools. */ namespace math { /** * \brief The roots of a third-order polynomial. * * \param[in] p The polynomial coefficients (poly = p[0]*x^3 + p[1]*x^2 ...). * \return The roots of the polynomial (only real ones). */ std::vector o3_roots( const std::vector & p ); /** * \brief Ferrari's method for computing the roots of a fourth order polynomial. * * \param[in] p The polynomial coefficients (poly = p(0,0)*x^4 + p(1,0)*x^3 ...). * \return The roots of the polynomial (only real ones). */ std::vector o4_roots( const Eigen::MatrixXd & p ); /** * \brief Ferrari's method for computing the roots of a fourth order polynomial. * With a different interface. * * \param[in] p The polynomial coefficients (poly = p[0]*x^4 + p[1]*x^3 ...). * \return The roots of the polynomial (only real ones). */ std::vector o4_roots( const std::vector & p ); } } #endif /* OPENGV_ROOTS_HPP_ */ opengv/include/opengv/absolute_pose/0000775016516101651610000000000013344612246016574 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/0000775016516101651610000000000013344612246020244 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/upnp2.hpp0000664016516101651610000000533713344612246022031 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_UPNP2_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_UPNP2_HPP_ #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace upnp { void setupAction_gj( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, Eigen::Matrix & Action ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_UPNP2_HPP_ */ opengv/include/opengv/absolute_pose/modules/gpnp2/0000775016516101651610000000000013344612246021272 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/gpnp2/modules.hpp0000664016516101651610000000734113344612246023460 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_GPNP2_MODULES_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_GPNP2_MODULES_HPP_ #include #include #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace gpnp2 { void init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ); void compute( Eigen::Matrix & groebnerMatrix ); void sPolynomial5( Eigen::Matrix & groebnerMatrix ); void sPolynomial6( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial7( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial8( Eigen::Matrix & groebnerMatrix ); void groebnerRow7_10_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial9( Eigen::Matrix & groebnerMatrix ); void groebnerRow8_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_GPNP2_MODULES_HPP_ */ opengv/include/opengv/absolute_pose/modules/upnp4.hpp0000664016516101651610000000534113344612246022026 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_UPNP4_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_UPNP4_HPP_ #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace upnp { void setupAction_sym_gj( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, Eigen::Matrix & Action ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_UPNP4_HPP_ */ opengv/include/opengv/absolute_pose/modules/gpnp5/0000775016516101651610000000000013344612246021275 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/gpnp5/modules.hpp0000664016516101651610000004457413344612246023474 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_GPNP5_MODULES_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_GPNP5_MODULES_HPP_ #include #include #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace gpnp5 { void init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Matrix & k, Eigen::Matrix & l, Eigen::Matrix & p, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ); void compute( Eigen::Matrix & groebnerMatrix ); void sPolynomial6( Eigen::Matrix & groebnerMatrix ); void sPolynomial7( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial8( Eigen::Matrix & groebnerMatrix ); void groebnerRow7_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial9( Eigen::Matrix & groebnerMatrix ); void groebnerRow8_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial10( Eigen::Matrix & groebnerMatrix ); void groebnerRow9_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial11( Eigen::Matrix & groebnerMatrix ); void groebnerRow10_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow6_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow9_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow6_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow9_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial12( Eigen::Matrix & groebnerMatrix ); void groebnerRow9_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow5_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow11_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow5_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow5_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial13( Eigen::Matrix & groebnerMatrix ); void groebnerRow8_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial14( Eigen::Matrix & groebnerMatrix ); void groebnerRow7_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow13_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial15( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial16( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial17( Eigen::Matrix & groebnerMatrix ); void groebnerRow7_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow5_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial18( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow17_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial19( Eigen::Matrix & groebnerMatrix ); void groebnerRow15_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow17_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow18_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow18_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial20( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow19_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial21( Eigen::Matrix & groebnerMatrix ); void groebnerRow8_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow9_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow20_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial22( Eigen::Matrix & groebnerMatrix ); void groebnerRow13_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial23( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow22_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial24( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow23_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial25( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow24_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow24_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial26( Eigen::Matrix & groebnerMatrix ); void groebnerRow11_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow25_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow25_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial27( Eigen::Matrix & groebnerMatrix ); void groebnerRow10_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow26_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow26_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial28( Eigen::Matrix & groebnerMatrix ); void groebnerRow27_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow27_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial29( Eigen::Matrix & groebnerMatrix ); void groebnerRow9_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow28_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow28_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial30( Eigen::Matrix & groebnerMatrix ); void groebnerRow18_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow24_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow29_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow29_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow29_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial31( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow18_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow25_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial32( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow6_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow18_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow26_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow31_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow31_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow31_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial33( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial34( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial35( Eigen::Matrix & groebnerMatrix ); void groebnerRow34_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow34_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial36( Eigen::Matrix & groebnerMatrix ); void groebnerRow35_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow35_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial37( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow36_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial38( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial39( Eigen::Matrix & groebnerMatrix ); void groebnerRow35_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow36_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial40( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial41( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_10010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_10010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_10100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_10100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_10100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow36_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial42( Eigen::Matrix & groebnerMatrix ); void groebnerRow39_02000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_02000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_02000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial43( Eigen::Matrix & groebnerMatrix ); void groebnerRow38_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow42_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow42_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow42_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_GPNP5_MODULES_HPP_ */ opengv/include/opengv/absolute_pose/modules/gpnp3/0000775016516101651610000000000013344612246021273 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/gpnp3/modules.hpp0000664016516101651610000001334613344612246023463 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_GPNP3_MODULES_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_GPNP3_MODULES_HPP_ #include #include #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace gpnp3 { void init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Matrix & k, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ); void compute( Eigen::Matrix & groebnerMatrix ); void sPolynomial4( Eigen::Matrix & groebnerMatrix ); void sPolynomial5( Eigen::Matrix & groebnerMatrix ); void groebnerRow4_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial6( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial7( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow6_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow6_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial8( Eigen::Matrix & groebnerMatrix ); void groebnerRow4_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow3_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial9( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow3_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial10( Eigen::Matrix & groebnerMatrix ); void groebnerRow4_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow9_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow9_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial11( Eigen::Matrix & groebnerMatrix ); void groebnerRow10_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial12( Eigen::Matrix & groebnerMatrix ); void groebnerRow10_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow11_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow11_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial13( Eigen::Matrix & groebnerMatrix ); void groebnerRow11_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial14( Eigen::Matrix & groebnerMatrix ); void groebnerRow13_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_GPNP3_MODULES_HPP_ */ opengv/include/opengv/absolute_pose/modules/gp3p/0000775016516101651610000000000013344612246021115 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/gp3p/modules.hpp0000664016516101651610000003347513344612246023312 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_GP3P_MODULES_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_GP3P_MODULES_HPP_ #include #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace gp3p { void init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & f, const Eigen::Matrix & v, const Eigen::Matrix & p ); void compute( Eigen::Matrix & groebnerMatrix ); void sPolynomial9( Eigen::Matrix & groebnerMatrix ); void sPolynomial10( Eigen::Matrix & groebnerMatrix ); void groebnerRow9_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial11( Eigen::Matrix & groebnerMatrix ); void groebnerRow10_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial12( Eigen::Matrix & groebnerMatrix ); void groebnerRow11_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial13( Eigen::Matrix & groebnerMatrix ); void groebnerRow10_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial14( Eigen::Matrix & groebnerMatrix ); void sPolynomial15( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial16( Eigen::Matrix & groebnerMatrix ); void groebnerRow15_010000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial17( Eigen::Matrix & groebnerMatrix ); void sPolynomial18( Eigen::Matrix & groebnerMatrix ); void groebnerRow15_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow17_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial19( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_010000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial20( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial21( Eigen::Matrix & groebnerMatrix ); void groebnerRow19_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow19_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial22( Eigen::Matrix & groebnerMatrix ); void groebnerRow19_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow18_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial23( Eigen::Matrix & groebnerMatrix ); void groebnerRow19_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow20_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial24( Eigen::Matrix & groebnerMatrix ); void groebnerRow15_100100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial25( Eigen::Matrix & groebnerMatrix ); void groebnerRow15_100010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow22_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial26( Eigen::Matrix & groebnerMatrix ); void groebnerRow15_100001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow23_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial27( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_100100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow24_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial28( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_100010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow25_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial29( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_100001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow26_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial30( Eigen::Matrix & groebnerMatrix ); void groebnerRow28_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow27_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial31( Eigen::Matrix & groebnerMatrix ); void groebnerRow29_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial32( Eigen::Matrix & groebnerMatrix ); void groebnerRow31_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow31_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial33( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial34( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial35( Eigen::Matrix & groebnerMatrix ); void groebnerRow34_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow34_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial36( Eigen::Matrix & groebnerMatrix ); void groebnerRow35_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow35_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial37( Eigen::Matrix & groebnerMatrix ); void sPolynomial38( Eigen::Matrix & groebnerMatrix ); void groebnerRow37_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow36_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial39( Eigen::Matrix & groebnerMatrix ); void groebnerRow38_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial40( Eigen::Matrix & groebnerMatrix ); void groebnerRow39_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial41( Eigen::Matrix & groebnerMatrix ); void groebnerRow40_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow40_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial42( Eigen::Matrix & groebnerMatrix ); void groebnerRow32_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow34_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow33_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow34_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow35_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow38_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow39_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow41_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial43( Eigen::Matrix & groebnerMatrix ); void groebnerRow33_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow37_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow42_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial44( Eigen::Matrix & groebnerMatrix ); void groebnerRow31_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow30_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial45( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow36_010000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow44_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial46( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow45_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial47( Eigen::Matrix & groebnerMatrix ); void groebnerRow36_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow43_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow46_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_GP3P_MODULES_HPP_ */ opengv/include/opengv/absolute_pose/modules/Epnp.hpp0000664016516101651610000001306413344612246021663 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ // Note: this code has been downloaded from the homepage of the "Computer // Vision Laboratory" at EPFL Lausanne, and was originally developped by the // authors of [4]. I only adapted it to Eigen. #ifndef OPENGV_ABSOLUTE_POSE_MODULES_EPNP_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_EPNP_HPP_ #include #include #include namespace opengv { namespace absolute_pose { namespace modules { class Epnp { public: Epnp(void); ~Epnp(); void set_maximum_number_of_correspondences(const int n); void reset_correspondences(void); void add_correspondence( const double X, const double Y, const double Z, const double x, const double y, const double z); double compute_pose(double R[3][3], double T[3]); void relative_error( double & rot_err, double & transl_err, const double Rtrue[3][3], const double ttrue[3], const double Rest[3][3], const double test[3]); void print_pose(const double R[3][3], const double t[3]); double reprojection_error(const double R[3][3], const double t[3]); private: void choose_control_points(void); void compute_barycentric_coordinates(void); void fill_M( Eigen::MatrixXd & M, const int row, const double * alphas, const double u, const double v); void compute_ccs(const double * betas, const Eigen::MatrixXd & ut); void compute_pcs(void); void solve_for_sign(void); void find_betas_approx_1( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double * betas); void find_betas_approx_2( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double * betas); void find_betas_approx_3( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double * betas); void qr_solve( Eigen::Matrix & A, Eigen::Matrix & b, Eigen::Matrix & X); double dot(const double * v1, const double * v2); double dist2(const double * p1, const double * p2); void compute_rho(Eigen::Matrix & Rho); void compute_L_6x10( const Eigen::MatrixXd & Ut, Eigen::Matrix & L_6x10 ); void gauss_newton( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double current_betas[4]); void compute_A_and_b_gauss_newton( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double cb[4], Eigen::Matrix & A, Eigen::Matrix & b); double compute_R_and_t( const Eigen::MatrixXd & Ut, const double * betas, double R[3][3], double t[3]); void estimate_R_and_t(double R[3][3], double t[3]); void copy_R_and_t( const double R_dst[3][3], const double t_dst[3], double R_src[3][3], double t_src[3]); void mat_to_quat(const double R[3][3], double q[4]); double uc, vc, fu, fv; double * pws, * us, * alphas, * pcs; int * signs; //added! int maximum_number_of_correspondences; int number_of_correspondences; double cws[4][3], ccs[4][3]; double cws_determinant; }; } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_EPNP_HPP_ */ opengv/include/opengv/absolute_pose/modules/gpnp4/0000775016516101651610000000000013344612246021274 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/gpnp4/modules.hpp0000664016516101651610000002272013344612246023460 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_GPNP4_MODULES_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_GPNP4_MODULES_HPP_ #include #include #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace gpnp4 { void init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Matrix & k, Eigen::Matrix & l, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ); void compute( Eigen::Matrix & groebnerMatrix ); void sPolynomial5( Eigen::Matrix & groebnerMatrix ); void sPolynomial6( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial7( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial8( Eigen::Matrix & groebnerMatrix ); void groebnerRow7_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial9( Eigen::Matrix & groebnerMatrix ); void groebnerRow7_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow5_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow6_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow7_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow8_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial10( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow9_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial11( Eigen::Matrix & groebnerMatrix ); void groebnerRow4_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow10_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow4_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial12( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow11_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial13( Eigen::Matrix & groebnerMatrix ); void groebnerRow6_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow4_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow12_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial14( Eigen::Matrix & groebnerMatrix ); void groebnerRow5_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow13_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial15( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow14_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial16( Eigen::Matrix & groebnerMatrix ); void groebnerRow13_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow15_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial17( Eigen::Matrix & groebnerMatrix ); void groebnerRow12_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow16_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial18( Eigen::Matrix & groebnerMatrix ); void groebnerRow14_0001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow14_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow17_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow17_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial19( Eigen::Matrix & groebnerMatrix ); void groebnerRow18_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial20( Eigen::Matrix & groebnerMatrix ); void groebnerRow18_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow19_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow19_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial21( Eigen::Matrix & groebnerMatrix ); void groebnerRow20_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow20_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial22( Eigen::Matrix & groebnerMatrix ); void groebnerRow19_0001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow19_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow20_0001_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow20_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow20_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial23( Eigen::Matrix & groebnerMatrix ); void groebnerRow20_1100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow21_1100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow22_1100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow19_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow22_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow22_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void groebnerRow22_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); void sPolynomial24( Eigen::Matrix & groebnerMatrix ); void groebnerRow23_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_GPNP4_MODULES_HPP_ */ opengv/include/opengv/absolute_pose/modules/gpnp1/0000775016516101651610000000000013344612246021271 5ustar dimadimaopengv/include/opengv/absolute_pose/modules/gpnp1/modules.hpp0000664016516101651610000000623113344612246023454 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_GPNP1_MODULES_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_GPNP1_MODULES_HPP_ #include #include #include #include namespace opengv { namespace absolute_pose { namespace modules { namespace gpnp1 { void init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ); void compute( Eigen::Matrix & groebnerMatrix ); void sPolynomial3( Eigen::Matrix & groebnerMatrix ); void sPolynomial4( Eigen::Matrix & groebnerMatrix ); void groebnerRow3_0_f( Eigen::Matrix & groebnerMatrix, int targetRow ); } } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_GPNP1_MODULES_HPP_ */ opengv/include/opengv/absolute_pose/modules/main.hpp0000664016516101651610000000777113344612246021715 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #ifndef OPENGV_ABSOLUTE_POSE_MODULES_MAIN_HPP_ #define OPENGV_ABSOLUTE_POSE_MODULES_MAIN_HPP_ #include #include namespace opengv { namespace absolute_pose { namespace modules { void p3p_kneip_main( const bearingVectors_t & f, const points_t & p, transformations_t & solutions ); void p3p_gao_main( const bearingVectors_t & f, const points_t & p, transformations_t & solutions ); void gp3p_main( const Eigen::Matrix3d & f, const Eigen::Matrix3d & v, const Eigen::Matrix3d & p, transformations_t & solutions ); void gpnp_main( const Eigen::Matrix & a, const Eigen::Matrix & V, const points_t & c, transformation_t & transformation ); double gpnp_evaluate( const Eigen::Matrix & solution, const points_t & c, translation_t & t, rotation_t & R ); void gpnp_optimize( const Eigen::Matrix & a, const Eigen::Matrix & V, const points_t & c, std::vector & factors ); void upnp_fill_s( const Eigen::Vector4d & quaternion, Eigen::Matrix & s ); void upnp_main( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, std::vector< std::pair, Eigen::aligned_allocator< std::pair > > & quaternions ); void upnp_main_sym( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, std::vector< std::pair, Eigen::aligned_allocator< std::pair > > & quaternions ); } } } #endif /* OPENGV_ABSOLUTE_POSE_MODULES_MAIN_HPP_ */ opengv/include/opengv/absolute_pose/NoncentralAbsoluteAdapter.hpp0000664016516101651610000001362513344612246024417 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file NoncentralAbsoluteAdapter.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the non-central absolute-pose algorithms. It maps opengv * types back to opengv types. */ #ifndef OPENGV_ABSOLUTE_POSE_NONCENTRALABSOLUTEADAPTER_HPP_ #define OPENGV_ABSOLUTE_POSE_NONCENTRALABSOLUTEADAPTER_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Check the documentation of the parent-class to understand the meaning of * an AbsoluteAdapter. This child-class is for the non-central case and holds * data in form of references to opengv-types. */ class NoncentralAbsoluteAdapter : public AbsoluteAdapterBase { protected: using AbsoluteAdapterBase::_t; using AbsoluteAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** A type defined for the camera-correspondences, see protected * class-members */ typedef std::vector camCorrespondences_t; /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const camCorrespondences_t & camCorrespondences, const points_t & points, const translations_t & camOffsets, const rotations_t & camRotations ); /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const camCorrespondences_t & camCorrespondences, const points_t & points, const translations_t & camOffsets, const rotations_t & camRotations, const rotation_t & R ); /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const camCorrespondences_t & camCorrespondences, const points_t & points, const translations_t & camOffsets, const rotations_t & camRotations, const translation_t & t, const rotation_t & R ); /** * \brief Destructor. */ virtual ~NoncentralAbsoluteAdapter(); //Access of correspondences /** See parent-class */ virtual opengv::bearingVector_t getBearingVector( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class */ virtual opengv::translation_t getCamOffset( size_t index ) const; /** See parent-class */ virtual opengv::rotation_t getCamRotation( size_t index ) const; /** See parent-class */ virtual opengv::point_t getPoint( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** Reference to the bearing-vectors expressed in the camera-frames */ const bearingVectors_t & _bearingVectors; /** Reference to an array of camera-indices for the bearing vectors. Length * equals to number of bearing-vectors, and elements are indices of cameras * in the _camOffsets and _camRotations arrays. */ const camCorrespondences_t & _camCorrespondences; /** Reference to the points expressed in the world-frame. */ const points_t & _points; /** Reference to positions of the different cameras seen from the * viewpoint. */ const translations_t & _camOffsets; /** Reference to rotations from the different cameras back to the * viewpoint. */ const rotations_t & _camRotations; }; } }; #endif /* OPENGV_ABSOLUTE_POSE_NONCENTRALABSOLUTEADAPTER_HPP_ */ opengv/include/opengv/absolute_pose/NoncentralAbsoluteMultiAdapter.hpp0000664016516101651610000001377713344612246025442 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file NoncentralAbsoluteMultiAdapter.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the non-central absolute-pose algorithms. It maps opengv * types back to opengv types. Manages multiple match-lists for each camera. * This allows to draw samples homogeneously over the cameras. */ #ifndef OPENGV_ABSOLUTE_POSE_NONCENTRALABSOLUTEMULTIADAPTER_HPP_ #define OPENGV_ABSOLUTE_POSE_NONCENTRALABSOLUTEMULTIADAPTER_HPP_ #include #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Check the documentation of the parent-class to understand the meaning of * an AbsoluteAdapter. This child-class is for the non-central case and holds * data in form of references to opengv-types. */ class NoncentralAbsoluteMultiAdapter : public AbsoluteMultiAdapterBase { protected: using AbsoluteMultiAdapterBase::_t; using AbsoluteMultiAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ NoncentralAbsoluteMultiAdapter( std::vector > bearingVectors, std::vector > points, const translations_t & camOffsets, const rotations_t & camRotations ); /** * \brief Destructor. */ virtual ~NoncentralAbsoluteMultiAdapter(); //camera-wise access of correspondences /** See parent-class */ virtual point_t getPoint( size_t frameIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual bearingVector_t getBearingVector( size_t frameIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual double getWeight( size_t frameIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual translation_t getMultiCamOffset( size_t frameIndex ) const; /** See parent-class */ virtual rotation_t getMultiCamRotation( size_t frameIndex ) const; /** See parent-class */ virtual size_t getNumberCorrespondences( size_t frameIndex ) const; /** See parent-class */ virtual size_t getNumberFrames() const; //Conversion to and from serialized indices /** See parent-class */ virtual std::vector convertMultiIndices( const std::vector > & multiIndices ) const; /** See parent-class */ virtual int convertMultiIndex( size_t frameIndex, size_t correspondenceIndex ) const; /** See parent-class */ virtual int multiFrameIndex( size_t index ) const; /** See parent-class */ virtual int multiCorrespondenceIndex( size_t index ) const; protected: /** References to multiple sets of bearing-vectors (the ones from each camera). */ std::vector > _bearingVectors; /** References to multiple sets of points (the ones from each camera). */ std::vector > _points; /** Reference to positions of the different cameras seen from the * viewpoint. */ const translations_t & _camOffsets; /** Reference to rotations from the different cameras back to the * viewpoint. */ const rotations_t & _camRotations; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiFrameIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector multiKeypointIndices; /** Initialized in constructor, used for (de)-serialiaztion of indices */ std::vector singleIndexOffsets; }; } }; #endif /* OPENGV_ABSOLUTE_POSE_NONCENTRALABSOLUTEADAPTER_HPP_ */ opengv/include/opengv/absolute_pose/MANoncentralAbsolute.hpp0000664016516101651610000001066113344612246023331 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MANoncentralAbsolute.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the non-central absolute-pose algorithms. It maps matlab * types to opengv types. */ #ifndef OPENGV_ABSOLUTE_POSE_MANONCENTRALABSOLUTE_HPP_ #define OPENGV_ABSOLUTE_POSE_MANONCENTRALABSOLUTE_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Check the documentation of the parent-class to understand the meaning of * an AbsoluteAdapter. This child-class is for the non-central case and holds * data in form of pointers to matlab-data. */ class MANoncentralAbsolute : public AbsoluteAdapterBase { protected: using AbsoluteAdapterBase::_t; using AbsoluteAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ MANoncentralAbsolute( const double * points, const double * bearingVectors, int numberPoints, int numberBearingVectors ); /** * Destructor */ virtual ~MANoncentralAbsolute(); //Access of correspondences /** See parent-class */ virtual opengv::bearingVector_t getBearingVector( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class */ virtual opengv::translation_t getCamOffset( size_t index ) const; /** See parent-class */ virtual opengv::rotation_t getCamRotation( size_t index ) const; /** See parent-class */ virtual opengv::point_t getPoint( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** A pointer to the point data */ const double * _points; /** A pointer to the bearing-vectors */ const double * _bearingVectors; /** The number of points */ int _numberPoints; /** The number of bearing vectors */ int _numberBearingVectors; }; } } #endif /* OPENGV_ABSOLUTE_POSE_MANONCENTRALABSOLUTE_HPP_ */ opengv/include/opengv/absolute_pose/MACentralAbsolute.hpp0000664016516101651610000001073413344612246022617 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MACentralAbsolute.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the central absolute-pose algorithms. It maps matlab types * back to opengv types. */ #ifndef OPENGV_ABSOLUTE_POSE_MACENTRALABSOLUTE_HPP_ #define OPENGV_ABSOLUTE_POSE_MACENTRALABSOLUTE_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Check the documentation of the parent-class to understand the meaning of * an AbsoluteAdapter. This child-class is for the central case and holds data * in form of pointers to matlab data. */ class MACentralAbsolute : public AbsoluteAdapterBase { protected: using AbsoluteAdapterBase::_t; using AbsoluteAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ MACentralAbsolute( const double * points, const double * bearingVectors, int numberPoints, int numberBearingVectors ); /** * Destructor */ virtual ~MACentralAbsolute(); //Access of correspondences /** See parent-class */ virtual opengv::bearingVector_t getBearingVector( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual opengv::translation_t getCamOffset( size_t index ) const; /** See parent-class Returns identity for this adapter. */ virtual opengv::rotation_t getCamRotation( size_t index ) const; /** See parent-class */ virtual opengv::point_t getPoint( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** A pointer to the point data */ const double * _points; /** A pointer to the bearing-vectors */ const double * _bearingVectors; /** The number of points */ int _numberPoints; /** The number of bearing vectors */ int _numberBearingVectors; }; } } #endif /* OPENGV_ABSOLUTE_POSE_MACENTRALABSOLUTE_HPP_ */ opengv/include/opengv/absolute_pose/AbsoluteAdapterBase.hpp0000664016516101651610000001577113344612246023172 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file AbsoluteAdapterBase.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the absolute-pose algorithms. */ #ifndef OPENGV_ABSOLUTE_POSE_ABSOLUTEADAPTERBASE_HPP_ #define OPENGV_ABSOLUTE_POSE_ABSOLUTEADAPTERBASE_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * The AbsoluteAdapterBase is the base-class for the visitors to the central * and non-central absolute pose algorithms. It provides a unified interface to * opengv-methods to access bearing-vectors, world points, priors or * known variables for the absolute pose, and the multi-camera configuration in * the non-central case. Derived classes may hold the data in any user-specific * format, and adapt to opengv-types. */ class AbsoluteAdapterBase { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. */ AbsoluteAdapterBase() : _t(Eigen::Vector3d::Zero()), _R(Eigen::Matrix3d::Identity()) {}; /** * \brief Constructor. * \param[in] R A prior or known value for the rotation from the viewpoint * to the world frame. */ AbsoluteAdapterBase( const opengv::rotation_t & R ) : _t(Eigen::Vector3d::Zero()), _R(R) {}; /** * \brief Constructor. * \param[in] t A prior or known value for the position of the viewpoint seen * from the world frame. * \param[in] R A prior or known value for the rotation from the viewpoint * to the world frame. */ AbsoluteAdapterBase( const opengv::translation_t & t, const opengv::rotation_t & R ) : _t(t), _R(R) {}; /** * \brief Destructor. */ virtual ~AbsoluteAdapterBase() {}; //Access of correspondences /** * \brief Retrieve the bearing vector of a correspondence. * \param[in] index The serialized index of the correspondence. * \return The corresponding bearing vector. */ virtual opengv::bearingVector_t getBearingVector(size_t index ) const = 0; /** * \brief Retrieve the weight of a correspondence. The weight is supposed to * reflect the quality of a correspondence, and typically is between * 0 and 1. * \param[in] index The serialized index of the correspondence. * \return The corresponding weight. */ virtual double getWeight( size_t index ) const = 0; /** * \brief Retrieve the position of a camera of a correspondence * seen from the viewpoint origin. * \param[in] index The serialized index of the correspondence. * \return The position of the corresponding camera seen from the viewpoint * origin. */ virtual opengv::translation_t getCamOffset( size_t index ) const = 0; /** * \brief Retrieve the rotation from a camera of a correspondence to the * viewpoint origin. * \param[in] index The serialized index of the correspondence. * \return The rotation from the corresponding camera back to the viewpoint * origin. */ virtual opengv::rotation_t getCamRotation( size_t index ) const = 0; /** * \brief Retrieve the world point of a correspondence. * \param[in] index The serialized index of the correspondence. * \return The corresponding world point. */ virtual opengv::point_t getPoint( size_t index ) const = 0; /** * \brief Retrieve the number of correspondences. * \return The number of correspondences. */ virtual size_t getNumberCorrespondences() const = 0; //Access of priors or known values /** * \brief Retrieve the prior or known value for the position. * \return The prior or known value for the position. */ opengv::translation_t gett() const { return _t; }; /** * \brief Set the prior or known value for the position. * \param[in] t The prior or known value for the position. */ void sett(const opengv::translation_t & t) { _t = t; }; /** * \brief Retrieve the prior or known value for the rotation. * \return The prior or known value for the rotation. */ opengv::rotation_t getR() const { return _R; }; /** * \brief Set the prior or known value for the rotation. * \param[in] R The prior or known value for the rotation. */ void setR(const opengv::rotation_t & R) { _R = R; }; protected: /** The prior or known value for the position of the viewpoint seen from the * world frame. Initialized to zero if not provided. */ opengv::translation_t _t; /** The prior or known value for the rotation from the viewpoint back to the * world frame. Initialized to identity if not provided. */ opengv::rotation_t _R; }; } }; #endif /* OPENGV_ABSOLUTE_POSE_ABSOLUTEADAPTERBASE_HPP_ */ opengv/include/opengv/absolute_pose/AbsoluteMultiAdapterBase.hpp0000664016516101651610000002255013344612246024176 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file AbsoluteMultiAdapterBase.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the absolute-pose algorithms. Intended for absolute non-central- * viewpoint problems. Access of correspondences etc. via an additional * frame-index referring to the camera. */ #ifndef OPENGV_ABSOLUTE_POSE_ABSOLUTEMULTIADAPTERBASE_HPP_ #define OPENGV_ABSOLUTE_POSE_ABSOLUTEMULTIADAPTERBASE_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * See the documentation of AbsoluteAdapterBase to understand the meaning of * an AbsoluteAdapter. AbsoluteMultiAdapterBase extends the interface of * AbsoluteAdapterBase by an additional frame-index for referring to a * camera. Intended for non-central absolute viewpoint problems, allowing * camera-wise access of correspondences. Derived classes need to implement * functionalities for deriving unique serialization of multi-indices. */ class AbsoluteMultiAdapterBase : public AbsoluteAdapterBase { protected: using AbsoluteAdapterBase::_t; using AbsoluteAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. */ AbsoluteMultiAdapterBase() : AbsoluteAdapterBase() {}; /** * \brief Constructor. * \param[in] R A prior or known value for the rotation from the viewpoint * to the world frame. */ AbsoluteMultiAdapterBase( const opengv::rotation_t & R ) : AbsoluteAdapterBase(R) {}; /** * \brief Constructor. * \param[in] t A prior or known value for the position of the viewpoint seen * from the world frame. * \param[in] R A prior or known value for the rotation from the viewpoint * to the world frame. */ AbsoluteMultiAdapterBase( const opengv::translation_t & t, const opengv::rotation_t & R ) : AbsoluteAdapterBase(t,R) {}; /** * \brief Destructor. */ virtual ~AbsoluteMultiAdapterBase() {}; //camera-wise access of correspondences /** * \brief Retrieve the bearing vector of a correspondence in a certain frame. * \param[in] frameIndex Index of the frame. * \param[in] correspondenceIndex Index of the correspondence in this frame. * \return The corresponding bearing vector. */ virtual opengv::bearingVector_t getBearingVector( size_t frameIndex, size_t correspondenceIndex ) const = 0; /** * \brief Retrieve the weight of a correspondence. The weight is supposed to * reflect the quality of a correspondence, and typically is between * 0 and 1. * \param[in] frameIndex Index of the frame. * \param[in] correspondenceIndex Index of the correspondence in this frame. * \return The corresponding weight. */ virtual double getWeight( size_t frameIndex, size_t correspondenceIndex ) const = 0; /** * \brief Retrieve the position of a camera seen from the viewpoint origin. * \param[in] frameIndex Index of the frame. * \return The position of the corresponding camera seen from the viewpoint * origin. */ virtual opengv::translation_t getMultiCamOffset( size_t frameIndex ) const = 0; /** * \brief Retrieve the rotation from a camera to the viewpoint frame. * \param[in] frameIndex Index of the frame. * \return The rotation from the corresponding camera back to the viewpoint * origin. */ virtual opengv::rotation_t getMultiCamRotation( size_t frameIndex ) const = 0; /** * \brief Retrieve the world point of a correspondence. * \param[in] frameIndex Index of the frame. * \param[in] correspondenceIndex Index of the correspondence in this frame. * \return The corresponding world point. */ virtual opengv::point_t getPoint( size_t frameIndex, size_t correspondenceIndex ) const = 0; /** * \brief Retrieve the number of correspondences for a camera. * \param[in] frameIndex Index of the camera. * \return The number of correspondences in this camera. */ virtual size_t getNumberCorrespondences( size_t frameIndex ) const = 0; /** * \brief Retrieve the number of cameras. * \return The number of cameras. */ virtual size_t getNumberFrames() const = 0; //Conversion to and from serialized indices /** * \brief Convert an array of (frameIndex,correspondenceIndex)-pairs into an * array of serialized indices. * \param[in] multiIndices Array of (frameIndex,correspondenceIndex)-pairs. * \return Array of single serialized indices referring uniquely to * (frameIndex,correspondenceIndex)-pairs. */ virtual std::vector convertMultiIndices( const std::vector > & multiIndices ) const = 0; /** * \brief Convert a (frameIndex,correspondenceIndex)-pair into a serialized * index. * \param[in] frameIndex The index of the camera. * \param[in] correspondenceIndex The index of the correspondence in the camera. * \return Array of single serialized indices referring uniquely to * (frameIndex,correspondenceIndex)-pairs. */ virtual int convertMultiIndex( size_t frameIndex, size_t correspondenceIndex ) const = 0; /** * \brief Get the frame-index corresponding to a serialized index. * \param[in] index The serialized index. * \return The frame index. */ virtual int multiFrameIndex( size_t index ) const = 0; /** * \brief Get the correspondence-index in a camera for a serialized index. * \param[in] index The serialized index. * \return The correspondence-index in the camera. */ virtual int multiCorrespondenceIndex( size_t index ) const = 0; //the classic interface (with serialized indices, used by the opengv-methods) /** See parent-class (no need to overload) */ virtual bearingVector_t getBearingVector( size_t index ) const { return getBearingVector( multiFrameIndex(index), multiCorrespondenceIndex(index) ); } /** See parent-class (no need to overload) */ virtual double getWeight( size_t index ) const { return getWeight( multiFrameIndex(index), multiCorrespondenceIndex(index) ); } /** See parent-class (no need to overload) */ virtual translation_t getCamOffset( size_t index ) const { return getMultiCamOffset( multiFrameIndex(index) ); } /** See parent-class (no need to overload) */ virtual rotation_t getCamRotation( size_t index ) const { return getMultiCamRotation( multiFrameIndex(index) ); } /** See parent-class (no need to overload) */ virtual point_t getPoint( size_t index ) const { return getPoint( multiFrameIndex(index), multiCorrespondenceIndex(index) ); } /** See parent-class (no need to overload) */ virtual size_t getNumberCorrespondences() const { size_t numberCorrespondences = 0; for(size_t i = 0; i < getNumberFrames(); i++) numberCorrespondences += getNumberCorrespondences(i); return numberCorrespondences; } }; } }; #endif /* OPENGV_ABSOLUTE_POSE_ABSOLUTEMULTIADAPTERBASE_HPP_ */ opengv/include/opengv/absolute_pose/CentralAbsoluteAdapter.hpp0000664016516101651610000001157013344612246023701 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file CentralAbsoluteAdapter.hpp * \brief Adapter-class for passing bearing-vector-to-point correspondences to * the central absolute-pose algorithms. It maps opengv types * back to opengv types. */ #ifndef OPENGV_ABSOLUTE_POSE_CENTRALABSOLUTEADAPTER_HPP_ #define OPENGV_ABSOLUTE_POSE_CENTRALABSOLUTEADAPTER_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Check the documentation of the parent-class to understand the meaning of * an AbsoluteAdapter. This child-class is for the central case and holds data * in form of references to opengv-types. */ class CentralAbsoluteAdapter : public AbsoluteAdapterBase { protected: using AbsoluteAdapterBase::_t; using AbsoluteAdapterBase::_R; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** * \brief Constructor. See protected class-members to understand parameters */ CentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const points_t & points ); /** * \brief Constructor. See protected class-members to understand parameters */ CentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const points_t & points, const rotation_t & R ); /** * \brief Constructor. See protected class-members to understand parameters */ CentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const points_t & points, const translation_t & t, const rotation_t & R ); /** * Destructor */ virtual ~CentralAbsoluteAdapter(); //Access of correspondences /** See parent-class */ virtual opengv::bearingVector_t getBearingVector( size_t index ) const; /** See parent-class */ virtual double getWeight( size_t index ) const; /** See parent-class. Returns zero for this adapter. */ virtual opengv::translation_t getCamOffset( size_t index ) const; /** See parent-class Returns identity for this adapter. */ virtual opengv::rotation_t getCamRotation( size_t index ) const; /** See parent-class */ virtual opengv::point_t getPoint( size_t index ) const; /** See parent-class */ virtual size_t getNumberCorrespondences() const; protected: /** Reference to the bearing-vectors expressed in the camera-frame */ const bearingVectors_t & _bearingVectors; /** Reference to the points expressed in the world-frame. */ const points_t & _points; }; } } #endif /* OPENGV_ABSOLUTE_POSE_CENTRALABSOLUTEADAPTER_HPP_ */ opengv/include/opengv/absolute_pose/methods.hpp0000664016516101651610000003426413344612246020761 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file absolute_pose/methods.hpp * \brief Methods for computing the absolute pose of a calibrated viewpoint. * * The collection includes both minimal and non-minimal solutions for * computing the absolute pose of a calibrated, either central or non-central * viewpoint. */ #ifndef OPENGV_ABSOLUTE_POSE_METHODS_HPP_ #define OPENGV_ABSOLUTE_POSE_METHODS_HPP_ #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** \brief Compute the pose of a central viewpoint with known rotation using two * point correspondences. * * \param[in] adapter Visitor holding bearing vectors, world points, and * known rotation. * \param[in] indices Indices of the two correspondences that are used for * deriving the translation. * \return The position of the viewpoint seen from the world frame. */ translation_t p2p( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose of a central viewpoint with known rotation using two * point correspondences. * * \param[in] adapter Visitor holding bearing vectors, world points, and * known rotation. * \param[in] index0 Index of the first correspondence used for deriving the * translation (use default value if only two vectors provided * by the visitor anyway). * \param[in] index1 Index of the second correspondence used for deriving the * translation (use default value if only two vectors provided * by the visitor anyway). * \return The position of the viewpoint seen from the world frame. */ translation_t p2p( const AbsoluteAdapterBase & adapter, size_t index0 = 0, size_t index1 = 1 ); /** * \brief Compute the pose of a central viewpoint using three point * correspondences and Kneip's method [1]. * * \param[in] adapter Visitor holding bearing vector to world point correspondences. * \param[in] indices Indices of the three correspondences that are used for * deriving the pose. * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world, frame, maximum 4 solutions). */ transformations_t p3p_kneip( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose of a central viewpoint using three point * correspondences and Kneip's method [1]. * * \param[in] adapter Visitor holding bearing vector to world point correspondences. * \param[in] index0 Index of the first correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \param[in] index1 Index of the second correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \param[in] index2 Index of the third correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame, maximum 4 solutions). */ transformations_t p3p_kneip( const AbsoluteAdapterBase & adapter, size_t index0 = 0, size_t index1 = 1, size_t index2 = 2 ); /** * \brief Compute the pose of a central viewpoint using three point correspondences * and Gao's method [2]. * * \param[in] adapter Visitor holding bearing vector to world point correspondences. * \param[in] indices Indices of the three correspondences that are used for * deriving the pose. * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame, maximum 4 solutions). */ transformations_t p3p_gao( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose of a central viewpoint using three point * correspondences and Gao's method [2]. * * \param[in] adapter Visitor holding bearing vector to world point correspondences. * \param[in] index0 Index of the first correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \param[in] index1 Index of the second correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \param[in] index2 Index of the third correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame, maximum 4 solutions). */ transformations_t p3p_gao( const AbsoluteAdapterBase & adapter, size_t index0 = 0, size_t index1 = 1, size_t index2 = 2 ); /** * \brief Compute the pose of a non-central viewpoint using three point * correspondences and Kneip's method [3]. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, plus the multi-camera configuration. * \param[in] indices Indices of the three correspondences that are used for * deriving the pose. * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from * viewpoint to world frame, maximum 8 solutions). */ transformations_t gp3p( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose of a non-central viewpoint using three point * correspondences and Kneip's method [3]. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, plus the multi-camera configuration. * \param[in] index0 Index of the first correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \param[in] index1 Index of the second correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \param[in] index2 Index of the third correspondence used for deriving the * pose (use default value if only three correspondences * provided anyway). * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from * viewpoint to world frame, maximum 8 solutions). */ transformations_t gp3p( const AbsoluteAdapterBase & adapter, size_t index0 = 0, size_t index1 = 1, size_t index2 = 2 ); /** * \brief Compute the pose of a central viewpoint using the EPnP method [4]. * Using all available correspondences. * * \param[in] adapter Visitor holding bearing vector to world point correspondences. * \return Pose of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformation_t epnp( const AbsoluteAdapterBase & adapter ); /** * \brief Compute the pose of a central viewpoint using the EPnP method [4]. * * \param[in] adapter Visitor holding bearing vector to world point correspondences. * \param[in] indices Indices of the n correspondences that are used for * deriving the pose. * \return Pose of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformation_t epnp( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose of a non-central viewpoint using the gPnP method [3]. * Using all available correspondences. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, plus the multi-camera configuration. * \return Pose of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformation_t gpnp( const AbsoluteAdapterBase & adapter ); /** * \brief Compute the pose of a non-central viewpoint using the gPnP method [3]. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, plus the multi-camera configuration. * \param[in] indices Indices of the n correspondences that are used for * deriving the pose. * \return Pose of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformation_t gpnp( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the poses of a non-central viewpoint using the uPnP method. * Using all available correspondences. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, plus the multi-camera configuration. * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformations_t upnp( const AbsoluteAdapterBase & adapter ); /** * \brief Compute the poses of a non-central viewpoint using the uPnP method. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, plus the multi-camera configuration. * \param[in] indices Indices of the n correspondences that are used for * deriving the pose. * \return Poses of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformations_t upnp( const AbsoluteAdapterBase & adapter, const std::vector & indices ); /** * \brief Compute the pose of a viewpoint using nonlinear optimization. Using * all available correspondences. Works for central and non-central case. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, the multi-camera configuration, plus * the initial values. * \return Pose of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformation_t optimize_nonlinear( const AbsoluteAdapterBase & adapter ); /** * \brief Compute the pose of a viewpoint using nonlinear optimization. Works * for central and non-central viewpoints. * * \param[in] adapter Visitor holding bearing vector to world point * correspondences, the multi-camera configuration, plus * the initial values. * \param[in] indices Indices of the n correspondences that are used for * deriving the pose. * \return Pose of viewpoint (position seen from world frame and orientation * from viewpoint to world frame, transforms points from viewpoint to * world frame). */ transformation_t optimize_nonlinear( const AbsoluteAdapterBase & adapter, const std::vector & indices ); } } #endif /* OPENGV_ABSOLUTE_POSE_METHODS_HPP_ */ opengv/include/opengv/OptimizationFunctor.hpp0000664016516101651610000000753613344612246020503 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file OptimizationFunctor.hpp * \brief Generic functor base for use with the Eigen-nonlinear optimization * toolbox. */ #ifndef OPENGV_OPTIMIZATIONFUNCTOR_HPP_ #define OPENGV_OPTIMIZATIONFUNCTOR_HPP_ #include #include #include using namespace std; using namespace Eigen; /** * \brief The namespace of this library. */ namespace opengv { /** * Generic functor base for use with the Eigen-nonlinear optimization * toolbox. Please refer to the Eigen-documentation for further information. */ template struct OptimizationFunctor { /** undocumented */ typedef _Scalar Scalar; /** undocumented */ enum { InputsAtCompileTime = NX, ValuesAtCompileTime = NY }; /** undocumented */ typedef Matrix InputType; /** undocumented */ typedef Matrix ValueType; /** undocumented */ typedef Matrix JacobianType; /** undocumented */ const int m_inputs; /** undocumented */ const int m_values; /** undocumented */ OptimizationFunctor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {} /** undocumented */ OptimizationFunctor(int inputs, int values) : m_inputs(inputs), m_values(values) {} /** undocumented */ int inputs() const { return m_inputs; } /** undocumented */ int values() const { return m_values; } }; } #endif /* OPENGV_OPTIMIZATIONFUNCTOR_HPP_ */ opengv/include/opengv/sac_problems/0000775016516101651610000000000013344612246016401 5ustar dimadimaopengv/include/opengv/sac_problems/point_cloud/0000775016516101651610000000000013344612246020720 5ustar dimadimaopengv/include/opengv/sac_problems/point_cloud/PointCloudSacProblem.hpp0000664016516101651610000001255313344612246025467 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file PointCloudSacProblem.hpp * \brief Functions for fitting a transformation model between two frames * containing point-clouds. Used in a random sample paradigm for * rejecting outliers in the correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_POINT_CLOUD_POINTCLOUDSACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_POINT_CLOUD_POINTCLOUDSACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the point-cloud alignment methods. */ namespace point_cloud { /** * Functions for fitting a transformation model between two frames containing * point-clouds. Using treept_arun. Used in a random sample paradigm for * rejecting outliers in the correspondences. */ class PointCloudSacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::point_cloud::PointCloudAdapterBase adapter_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ PointCloudSacProblem(adapter_t & adapter, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ PointCloudSacProblem( adapter_t & adapter, const std::vector & indices, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter) { setIndices(indices); }; /** * Destructor. */ virtual ~PointCloudSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_POINT_CLOUD_POINTCLOUDSACPROBLEM_HPP_ opengv/include/opengv/sac_problems/relative_pose/0000775016516101651610000000000013344612246021242 5ustar dimadimaopengv/include/opengv/sac_problems/relative_pose/CentralRelativePoseSacProblem.hpp0000664016516101651610000001376313344612246027650 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file CentralRelativePoseSacProblem.hpp * \brief Functions for fitting a relative-pose model to a set of bearing-vector * correspondences, using different algorithms (central). Used with a * random sample paradigm for rejecting outlier correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_CENTRALRELATIVEPOSESACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_CENTRALRELATIVEPOSESACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Provides functions for fitting an absolute-pose model to a set of * bearing-vector to point correspondences, using different algorithms (only * central case). Used in a sample-consenus paradigm for rejecting * outlier correspondences. */ class CentralRelativePoseSacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeAdapterBase adapter_t; /** The possible algorithms for solving this problem */ typedef enum Algorithm { STEWENIUS = 0, // [5] NISTER = 1, // [6] SEVENPT = 2, // [8] EIGHTPT = 3 // [9,10] } algorithm_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] algorithm The algorithm we want to use. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ CentralRelativePoseSacProblem(adapter_t & adapter, algorithm_t algorithm, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] algorithm The algorithm we want to use. * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ CentralRelativePoseSacProblem( adapter_t & adapter, algorithm_t algorithm, const std::vector & indices, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm) { setIndices(indices); }; /** * Destructor. */ virtual ~CentralRelativePoseSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; /** The algorithm we are using. */ algorithm_t _algorithm; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_CENTRALRELATIVEPOSESACPROBLEM_HPP_ opengv/include/opengv/sac_problems/relative_pose/EigensolverSacProblem.hpp0000664016516101651610000001345713344612246026217 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file EigensolverSacProblem.hpp * \brief Functions for fitting a relative-pose model to a set of bearing-vector * correspondences, using the eigensolver algorithm. Used with a random * sample paradigm for rejecting outlier correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_EIGENSOLVERSACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_EIGENSOLVERSACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Functions for fitting a relative-pose model to a set of bearing-vector * correspondences, using the eigensolver algorithm [11]. Used with a random * sample paradigm for rejecting outlier correspondences. */ class EigensolverSacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (eigensolverOutput) */ typedef eigensolverOutput_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeAdapterBase adapter_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] sampleSize Number of correspondences used for generating hypotheses. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ EigensolverSacProblem(adapter_t & adapter, size_t sampleSize, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _sampleSize(sampleSize) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] sampleSize Number of correspondences used for generating hypotheses. * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ EigensolverSacProblem( adapter_t & adapter, size_t sampleSize, const std::vector & indices, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _sampleSize(sampleSize) { setIndices(indices); }; /** * Destructor. */ virtual ~EigensolverSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector &indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; /** The number of samples we are using for generating a hypothesis. */ size_t _sampleSize; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_EIGENSOLVERSACPROBLEM_HPP_ opengv/include/opengv/sac_problems/relative_pose/MultiCentralRelativePoseSacProblem.hpp0000664016516101651610000001443313344612246030656 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MultiCentralRelativePoseSacProblem.hpp * \brief Functions for fitting a multi relative-pose model to sets of * bearing-vector correspondences between multiple viewpoints. Exploits * mutual agreement. Used within a multi random-sample paradigm for * rejecting outlier correspondences. Experimental! */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_MULTICENTRALRELATIVEPOSESACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_MULTICENTRALRELATIVEPOSESACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Functions for fitting a multi relative-pose model to sets of * bearing-vector correspondences between multiple viewpoints. Exploits mutual * agreement. Used within a multi random-sample paradigm for rejecting outlier * correspondences. Experimental! Currently using eightpt [9,10]. */ class MultiCentralRelativePoseSacProblem : public sac::MultiSampleConsensusProblem< transformations_t > { public: /** The model we are trying to fit (multiple transformations) */ typedef transformations_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeMultiAdapterBase adapter_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] sampleSize The number of samples for each "sub"-hypothesis. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ MultiCentralRelativePoseSacProblem(adapter_t & adapter, int sampleSize, bool randomSeed = true) : sac::MultiSampleConsensusProblem (randomSeed), _adapter(adapter), _sampleSize(sampleSize) { std::vector numberCorrespondences; for(size_t i = 0; i < adapter.getNumberPairs(); i++) numberCorrespondences.push_back(adapter.getNumberCorrespondences(i)); setUniformIndices(numberCorrespondences); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] indices A vector of multi-indices to be used from all available * correspondences. * \param[in] sampleSize The number of samples for each "sub"-hypothesis. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ MultiCentralRelativePoseSacProblem( adapter_t & adapter, const std::vector > & indices, int sampleSize, bool randomSeed = true) : sac::MultiSampleConsensusProblem (randomSeed), _adapter(adapter), _sampleSize(sampleSize) { setIndices(indices); }; /** * Destructor. */ virtual ~MultiCentralRelativePoseSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector< std::vector > & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector > & indices, std::vector > & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector > & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual std::vector getSampleSizes() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; /** The number of samples for each "sub"-hypothesis. */ int _sampleSize; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_MULTICENTRALRELATIVEPOSESACPROBLEM_HPP_ opengv/include/opengv/sac_problems/relative_pose/NoncentralRelativePoseSacProblem.hpp0000664016516101651610000001456513344612246030364 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file NoncentralRelativePoseSacProblem.hpp * \brief Functions for fitting a relative-pose model to a set of bearing-vector * correspondences from a multi-camera system (non-central). Used with * a random-sample paradigm for rejecting outlier-correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_NONCENTRALRELATIVEPOSESACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_NONCENTRALRELATIVEPOSESACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Functions for fitting a relative-pose model to a set of bearing-vector * correspondences from a multi-camera system (non-central). Can switch back to * central as well in case only one camera is present. Otherwise using * seventeenpt [12]. Used with a random-sample paradigm for rejecting * outlier-correspondences. */ class NoncentralRelativePoseSacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeAdapterBase adapter_t; /** The possible algorithms for solving this problem */ typedef enum Algorithm { SIXPT = 0, // [16] GE = 1, // [] SEVENTEENPT = 2 // [12] } algorithm_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] algorithm The algorithm to use. * \param[in] asCentral Solve problem with only one camera? * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ NoncentralRelativePoseSacProblem( adapter_t & adapter, algorithm_t algorithm, bool asCentral = false, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm), _asCentral(asCentral) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] algorithm The algorithm to use * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] asCentral Solve problem with only one camera? * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ NoncentralRelativePoseSacProblem( adapter_t & adapter, algorithm_t algorithm, const std::vector & indices, bool asCentral = false, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm), _asCentral(asCentral) { setIndices(indices); }; /** * Destructor. */ virtual ~NoncentralRelativePoseSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; /** The algorithm we are using. */ algorithm_t _algorithm; /** Use the central algorithm? (only one camera?). */ bool _asCentral; }; } } } #endif /* OPENGV_SAC_PROBLEMS_RELATIVE_POSE_NONCENTRALRELATIVEPOSESACPROBLEM_HPP_ */ opengv/include/opengv/sac_problems/relative_pose/RotationOnlySacProblem.hpp0000664016516101651610000001275013344612246026371 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file RotationOnlySacProblem.hpp * \brief Functions for fitting a rotation-only model to a set of bearing-vector * correspondences. The viewpoints are assumed to be separated by * rotation only. Used within a random-sample paradigm for rejecting * outlier correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_ROTATIONONLYSACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_ROTATIONONLYSACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Functions for fitting a rotation-only model to a set of bearing-vector * correspondences (using twopt_rotationOnly). The viewpoints are assumed to * be separated by rotation only. Used within a random-sample paradigm for * rejecting outlier correspondences. */ class RotationOnlySacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (rotation) */ typedef rotation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeAdapterBase adapter_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ RotationOnlySacProblem(adapter_t & adapter, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ RotationOnlySacProblem( adapter_t & adapter, const std::vector & indices, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter) { setIndices(indices); }; /** * Destructor. */ virtual ~RotationOnlySacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_ROTATIONONLYSACPROBLEM_HPP_ opengv/include/opengv/sac_problems/relative_pose/MultiNoncentralRelativePoseSacProblem.hpp0000664016516101651610000001600413344612246031365 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MultiNoncentralRelativePoseSacProblem.hpp * \brief Functions for fitting a relative-pose model to a set of bearing-vector * correspondences from a multi-camera system (non-central). Uses * RelativeMultiAdapterBase for managing correspondence-lists between * individual pairs of views, enabling homogeneous sampling over the * views. Used in a random-sample paradigm for rejecting outlier * correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_MULTINONCENTRALRELATIVEPOSESACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_MULTINONCENTRALRELATIVEPOSESACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Functions for fitting a relative-pose model to a set of bearing-vector * correspondences from a multi-camera system (non-central). Can switch back to * central as well in case only one camera is present. Otherwise using * seventeenpt [12]. Uses RelativeMultiAdapterBase for managing * correspondence-lists between individual pairs of views, enabling homogeneous * sampling over the views. Used in a random-sample paradigm for rejecting * outlier correspondences. */ class MultiNoncentralRelativePoseSacProblem : public sac::MultiSampleConsensusProblem< transformation_t > { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeMultiAdapterBase adapter_t; /** The possible algorithms for solving this problem */ typedef enum Algorithm { SIXPT = 0, // [16] GE = 1, // [] SEVENTEENPT = 2 // [12] } algorithm_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] algorithm The algorithm to use. * \param[in] asCentral Solve problem with only one camera? * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ MultiNoncentralRelativePoseSacProblem( adapter_t & adapter, algorithm_t algorithm, bool asCentral = false, bool randomSeed = true) : sac::MultiSampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm), _asCentral(asCentral) { std::vector numberCorrespondences; for(size_t i = 0; i < adapter.getNumberPairs(); i++) numberCorrespondences.push_back(adapter.getNumberCorrespondences(i)); setUniformIndices(numberCorrespondences); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] algorithm The algorithm to use. * \param[in] indices A vector of multi-indices to be used from all available * correspondences. * \param[in] asCentral Solve problem with only one camera? * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ MultiNoncentralRelativePoseSacProblem( adapter_t & adapter, algorithm_t algorithm, const std::vector > & indices, bool asCentral = false, bool randomSeed = true) : sac::MultiSampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm), _asCentral(asCentral) { setIndices(indices); }; /** * Destructor. */ virtual ~MultiNoncentralRelativePoseSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector< std::vector > & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector > & indices, std::vector > & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector > & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual std::vector getSampleSizes() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; /** The algorithm we are using. */ algorithm_t _algorithm; /** Use the central algorithm? (only one camera?). */ bool _asCentral; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_MULTINONCENTRALRELATIVEPOSESACPROBLEM_HPP_ opengv/include/opengv/sac_problems/relative_pose/TranslationOnlySacProblem.hpp0000664016516101651610000001302013344612246027057 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file TranslationOnlySacProblem.hpp * \brief Functions for fitting a relative-pose model to a set of bearing-vector * correspondences. The viewpoints are assumed to be separated by * translation only. Used within a random-sample paradigm for rejecting * outlier correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_TRANSLATIONONLYSACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_RELATIVE_POSE_TRANSLATIONONLYSACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the relative pose methods. */ namespace relative_pose { /** * Functions for fitting a relative-pose model to a set of bearing-vector * correspondences (using twopt). The viewpoints are assumed to be separated by * translation only. Used within a random-sample paradigm for rejecting outlier * correspondences. */ class TranslationOnlySacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::relative_pose::RelativeAdapterBase adapter_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ TranslationOnlySacProblem(adapter_t & adapter, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vector correspondences etc. * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ TranslationOnlySacProblem( adapter_t & adapter, const std::vector & indices, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter) { setIndices(indices); }; /** * Destructor. */ virtual ~TranslationOnlySacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data. */ adapter_t & _adapter; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_RELATIVE_POSE_TRANSLATIONONLYSACPROBLEM_HPP_ opengv/include/opengv/sac_problems/absolute_pose/0000775016516101651610000000000013344612246021245 5ustar dimadimaopengv/include/opengv/sac_problems/absolute_pose/AbsolutePoseSacProblem.hpp0000664016516101651610000001411613344612246026336 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file AbsolutePoseSacProblem.hpp * \brief Functions for fitting an absolute-pose model to a set of * bearing-vector-point correspondences, using different algorithms * (central and non-central one). Used in a sample-consenus paradigm for * rejecting outlier correspondences. */ #ifndef OPENGV_SAC_PROBLEMS_ABSOLUTE_POSE_ABSOLUTEPOSESACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_ABSOLUTE_POSE_ABSOLUTEPOSESACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Provides functions for fitting an absolute-pose model to a set of * bearing-vector to point correspondences, using different algorithms (central * and non-central ones). Used in a sample-consenus paradigm for rejecting * outlier correspondences. */ class AbsolutePoseSacProblem : public sac::SampleConsensusProblem { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::absolute_pose::AbsoluteAdapterBase adapter_t; /** The possible algorithms for solving this problem */ typedef enum Algorithm { TWOPT = 0, // central, with rotation prior KNEIP = 1, // central [1] GAO = 2, // central [2] EPNP = 3, // central [4] GP3P = 4 // non-central [3] } algorithm_t; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vectors, world points, etc. * \param[in] algorithm The algorithm we want to use. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ AbsolutePoseSacProblem(adapter_t & adapter, algorithm_t algorithm, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm) { setUniformIndices(adapter.getNumberCorrespondences()); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vectors, world points, etc. * \param[in] algorithm The algorithm we want to use. * \param[in] indices A vector of indices to be used from all available * correspondences. * \param[in] randomSeed Whether to seed the random number generator with * the current time. */ AbsolutePoseSacProblem( adapter_t & adapter, algorithm_t algorithm, const std::vector & indices, bool randomSeed = true) : sac::SampleConsensusProblem (randomSeed), _adapter(adapter), _algorithm(algorithm) { setIndices(indices); }; /** * Destructor. */ virtual ~AbsolutePoseSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual int getSampleSize() const; protected: /** The adapter holding all input data */ adapter_t & _adapter; /** The algorithm we are using */ algorithm_t _algorithm; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_ABSOLUTE_POSE_ABSOLUTEPOSESACPROBLEM_HPP_ opengv/include/opengv/sac_problems/absolute_pose/MultiNoncentralAbsolutePoseSacProblem.hpp0000664016516101651610000001361613344612246031401 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ /** * \file MultiNoncentralAbsolutePoseSacProblem.hpp * \brief Functions for fitting an absolute-pose model to a set of * bearing-vector-point correspondences, using different algorithms * (central and non-central one). Used in a sample-consenus paradigm for * rejecting outlier correspondences, which does homogeneous sampling */ #ifndef OPENGV_SAC_PROBLEMS_ABSOLUTE_POSE_MULTINONCENTRALABSOLUTEPOSESACPROBLEM_HPP_ #define OPENGV_SAC_PROBLEMS_ABSOLUTE_POSE_MULTINONCENTRALABSOLUTEPOSESACPROBLEM_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus problems. */ namespace sac_problems { /** * \brief The namespace for the absolute pose methods. */ namespace absolute_pose { /** * Provides functions for fitting an absolute-pose model to a set of * bearing-vector to point correspondences, using different algorithms (central * and non-central ones). Used in a sample-consenus paradigm for rejecting * outlier correspondences. */ class MultiNoncentralAbsolutePoseSacProblem : public sac::MultiSampleConsensusProblem { public: /** The model we are trying to fit (transformation) */ typedef transformation_t model_t; /** The type of adapter that is expected by the methods */ typedef opengv::absolute_pose::AbsoluteMultiAdapterBase adapter_t; //This multisacproblem uses either gp3p or p3p for finding the relative pose /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vectors, world points, etc. */ MultiNoncentralAbsolutePoseSacProblem(adapter_t & adapter, bool asCentral = false) : sac::MultiSampleConsensusProblem (), _adapter(adapter), _asCentral(asCentral) { std::vector numberCorrespondences; for(size_t i = 0; i < adapter.getNumberFrames(); i++) numberCorrespondences.push_back(adapter.getNumberCorrespondences(i)); setUniformIndices(numberCorrespondences); }; /** * \brief Constructor. * \param[in] adapter Visitor holding bearing vectors, world points, etc. * \param[in] indices A vector of indices to be used from all available * correspondences. */ MultiNoncentralAbsolutePoseSacProblem( adapter_t & adapter, const std::vector > & indices, bool asCentral = false ) : sac::MultiSampleConsensusProblem (), _adapter(adapter), _asCentral(asCentral) { setIndices(indices); }; /** * Destructor. */ virtual ~MultiNoncentralAbsolutePoseSacProblem() {}; /** * \brief See parent-class. */ virtual bool computeModelCoefficients( const std::vector< std::vector > & indices, model_t & outModel) const; /** * \brief See parent-class. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector > & indices, std::vector > & scores) const; /** * \brief See parent-class. */ virtual void optimizeModelCoefficients( const std::vector > & inliers, const model_t & model, model_t & optimized_model); /** * \brief See parent-class. */ virtual std::vector getSampleSizes() const; protected: /** The adapter holding all input data */ adapter_t & _adapter; /** Use the central algorithm? (only one camera?). */ bool _asCentral; }; } } } #endif //#ifndef OPENGV_SAC_PROBLEMS_ABSOLUTE_POSE_MULTINONCENTRALABSOLUTEPOSESACPROBLEM_HPP_ opengv/include/opengv/sac/0000775016516101651610000000000013635643413014501 5ustar dimadimaopengv/include/opengv/sac/implementation/0000775016516101651610000000000013635643413017526 5ustar dimadimaopengv/include/opengv/sac/implementation/MultiSampleConsensusProblem.hpp0000664016516101651610000001764313635643413025730 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS #include template opengv::sac::MultiSampleConsensusProblem::MultiSampleConsensusProblem( bool randomSeed) : max_sample_checks_(10) { rng_dist_.reset(new std::uniform_int_distribution<>( 0, std::numeric_limits::max () )); // Create a random number generator object if (randomSeed) rng_alg_.seed(static_cast(time(0)) + static_cast(clock()) ); else rng_alg_.seed(12345u); rng_gen_.reset(new std::function(std::bind(*rng_dist_, rng_alg_))); } template opengv::sac::MultiSampleConsensusProblem::~MultiSampleConsensusProblem() {} template bool opengv::sac::MultiSampleConsensusProblem::isSampleGood( const std::vector< std::vector > & sample) const { // Default implementation return true; } template void opengv::sac::MultiSampleConsensusProblem::drawIndexSample( std::vector< std::vector > & sample) { for( size_t subIter = 0; subIter < sample.size(); subIter++ ) { size_t sample_size = sample[subIter].size(); size_t index_size = shuffled_indices_[subIter].size(); for( unsigned int i = 0; i < sample_size; ++i ) { // The 1/(RAND_MAX+1.0) trick is when the random numbers are not uniformly // distributed and for small modulo elements, that does not matter // (and nowadays, random number generators are good) //std::swap (shuffled_indices_[i], shuffled_indices_[i + (rand () % (index_size - i))]); std::swap( shuffled_indices_[subIter][i], shuffled_indices_[subIter][i + (rnd() % (index_size - i))] ); } std::copy( shuffled_indices_[subIter].begin (), shuffled_indices_[subIter].begin () + sample_size, sample[subIter].begin () ); } } template void opengv::sac::MultiSampleConsensusProblem::getSamples( int &iterations, std::vector< std::vector > &samples ) { std::vector sampleSizes = getSampleSizes(); samples.resize( sampleSizes.size() ); for( size_t subIter = 0; subIter < samples.size(); subIter++ ) { // We're assuming that indices_ have already been set in the constructor if( (*indices_)[subIter].size() < (size_t) sampleSizes[subIter] ) { fprintf( stderr, "[sm::SampleConsensusModel::getSamples] Can not select %d unique points out of %zu!\n", sampleSizes[subIter], (*indices_)[subIter].size() ); // one of these will make it stop :) samples.clear(); iterations = std::numeric_limits::max(); return; } // Get a second point which is different than the first samples[subIter].resize( sampleSizes[subIter] ); } for( int iter = 0; iter < max_sample_checks_; ++iter ) { drawIndexSample(samples); // If it's a good sample, stop here if (isSampleGood (samples)) return; } size_t multiSampleSize = 0; for( size_t multiIter = 0; multiIter < samples.size(); multiIter++ ) multiSampleSize += samples[multiIter].size(); fprintf( stdout, "[sm::SampleConsensusModel::getSamples] WARNING: Could not select %zu sample points in %d iterations!\n", multiSampleSize, max_sample_checks_ ); samples.clear(); } template std::shared_ptr< std::vector< std::vector > > opengv::sac::MultiSampleConsensusProblem::getIndices() const { return indices_; } template void opengv::sac::MultiSampleConsensusProblem::getDistancesToModel( const model_t & model_coefficients, std::vector > & distances ) { getSelectedDistancesToModel( model_coefficients, *indices_, distances ); } template void opengv::sac::MultiSampleConsensusProblem::setUniformIndices( std::vector N) { indices_.reset( new std::vector< std::vector >() ); indices_->resize(N.size()); for( size_t j = 0; j < N.size(); j++ ) { (*indices_)[j].resize(N[j]); for( int i = 0; i < N[j]; ++i ) (*indices_)[j][i] = i; } shuffled_indices_ = *indices_; } template void opengv::sac::MultiSampleConsensusProblem::setIndices( const std::vector< std::vector > & indices ) { indices_.reset( new std::vector >(indices) ); shuffled_indices_ = *indices_; } template int opengv::sac::MultiSampleConsensusProblem::rnd() { return ((*rng_gen_) ()); } template void opengv::sac::MultiSampleConsensusProblem::selectWithinDistance( const model_t & model_coefficients, const double threshold, std::vector > &inliers ) { std::vector > dist; dist.resize(indices_->size()); inliers.clear(); inliers.resize(indices_->size()); for( size_t j = 0; j < indices_->size(); j++ ) dist[j].reserve((*indices_)[j].size()); getDistancesToModel( model_coefficients, dist ); for( size_t j = 0; j < indices_->size(); j++ ) { inliers[j].clear(); inliers[j].reserve((*indices_)[j].size()); for(size_t i = 0; i < dist[j].size(); ++i) { if( dist[j][i] < threshold ) inliers[j].push_back( (*indices_)[j][i] ); } } } template int opengv::sac::MultiSampleConsensusProblem::countWithinDistance( const model_t & model_coefficients, const double threshold ) { std::vector< std::vector > dist; dist.resize(indices_->size()); for( size_t j = 0; j < indices_->size(); j++ ) dist[j].reserve((*indices_)[j].size()); getDistancesToModel( model_coefficients, dist ); int count = 0; for( size_t j = 0; j < indices_->size(); j++ ) { for( size_t i = 0; i < dist[j].size(); ++i ) { if( dist[j][i] < threshold ) ++count; } } return count; } opengv/include/opengv/sac/implementation/SampleConsensusProblem.hpp0000664016516101651610000001522013635643413024702 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS #include #include template opengv::sac::SampleConsensusProblem::SampleConsensusProblem( bool randomSeed) : max_sample_checks_(10) { rng_dist_.reset(new std::uniform_int_distribution<>( 0, std::numeric_limits::max() )); // Create a random number generator object if(randomSeed) rng_alg_.seed(static_cast(time(0)) + static_cast(clock()) ); else rng_alg_.seed(12345u); rng_gen_.reset(new std::function(std::bind(*rng_dist_, rng_alg_))); } template opengv::sac::SampleConsensusProblem::~SampleConsensusProblem() {} template bool opengv::sac::SampleConsensusProblem::isSampleGood( const std::vector & sample) const { // Default implementation return true; } template void opengv::sac::SampleConsensusProblem::drawIndexSample( std::vector & sample) { size_t sample_size = sample.size(); size_t index_size = shuffled_indices_.size(); for( unsigned int i = 0; i < sample_size; ++i ) { // The 1/(RAND_MAX+1.0) trick is when the random numbers are not uniformly // distributed and for small modulo elements, that does not matter // (and nowadays, random number generators are good) //std::swap (shuffled_indices_[i], shuffled_indices_[i + (rand () % (index_size - i))]); std::swap( shuffled_indices_[i], shuffled_indices_[i + (rnd() % (index_size - i))] ); } std::copy( shuffled_indices_.begin(), shuffled_indices_.begin() + sample_size, sample.begin() ); } template void opengv::sac::SampleConsensusProblem::getSamples( int &iterations, std::vector &samples) { // We're assuming that indices_ have already been set in the constructor if (indices_->size() < (size_t)getSampleSize()) { fprintf( stderr, "[sm::SampleConsensusModel::getSamples] Can not select %zu unique points out of %zu!\n", (size_t) getSampleSize(), indices_->size() ); // one of these will make it stop :) samples.clear(); iterations = std::numeric_limits::max(); return; } // Get a second point which is different than the first samples.resize( getSampleSize() ); for( int iter = 0; iter < max_sample_checks_; ++iter ) { drawIndexSample(samples); // If it's a good sample, stop here if(isSampleGood(samples)) return; } fprintf( stdout, "[sm::SampleConsensusModel::getSamples] WARNING: Could not select %d sample points in %d iterations!\n", getSampleSize(), max_sample_checks_ ); samples.clear(); } template std::shared_ptr< std::vector > opengv::sac::SampleConsensusProblem::getIndices() const { return indices_; } template void opengv::sac::SampleConsensusProblem::getDistancesToModel( const model_t & model_coefficients, std::vector & distances ) { getSelectedDistancesToModel( model_coefficients, *indices_, distances ); } template void opengv::sac::SampleConsensusProblem::setUniformIndices(int N) { indices_.reset( new std::vector() ); indices_->resize(N); for( int i = 0; i < N; ++i ) (*indices_)[i] = i; shuffled_indices_ = *indices_; } template void opengv::sac::SampleConsensusProblem::setIndices( const std::vector & indices ) { indices_.reset( new std::vector(indices) ); shuffled_indices_ = *indices_; } template int opengv::sac::SampleConsensusProblem::rnd() { return ((*rng_gen_)()); } template void opengv::sac::SampleConsensusProblem::selectWithinDistance( const model_t & model_coefficients, const double threshold, std::vector &inliers ) { std::vector dist; dist.reserve(indices_->size()); getDistancesToModel( model_coefficients, dist ); inliers.clear(); inliers.reserve(indices_->size()); for( size_t i = 0; i < dist.size(); ++i ) { if( dist[i] < threshold ) inliers.push_back( (*indices_)[i] ); } } template int opengv::sac::SampleConsensusProblem::countWithinDistance( const model_t & model_coefficients, const double threshold) { std::vector dist; dist.reserve(indices_->size()); getDistancesToModel( model_coefficients, dist ); int count = 0; for( size_t i = 0; i < dist.size(); ++i ) { if( dist[i] < threshold ) ++count; } return count; } opengv/include/opengv/sac/implementation/Ransac.hpp0000664016516101651610000001332613344612246021450 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS template opengv::sac::Ransac

::Ransac( int maxIterations, double threshold, double probability) : SampleConsensus

(maxIterations, threshold, probability) {} template opengv::sac::Ransac

::~Ransac(){} template bool opengv::sac::Ransac::computeModel( int debug_verbosity_level) { typedef PROBLEM_T problem_t; typedef typename problem_t::model_t model_t; iterations_ = 0; int n_best_inliers_count = -INT_MAX; double k = 1.0; std::vector selection; model_t model_coefficients; int n_inliers_count = 0; unsigned skipped_count = 0; // supress infinite loops by just allowing 10 x maximum allowed iterations for // invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate while( iterations_ < k && skipped_count < max_skip ) { // Get X samples which satisfy the model criteria sac_model_->getSamples( iterations_, selection ); if(selection.empty()) { fprintf(stderr, "[sm::RandomSampleConsensus::computeModel] No samples could be selected!\n"); break; } // Search for inliers in the point cloud for the current plane model M if(!sac_model_->computeModelCoefficients( selection, model_coefficients )) { //++iterations_; ++ skipped_count; continue; } // Select the inliers that are within threshold_ from the model //sac_model_->selectWithinDistance( model_coefficients, threshold_, inliers ); //if(inliers.empty() && k > 1.0) // continue; n_inliers_count = sac_model_->countWithinDistance( model_coefficients, threshold_ ); // Better match ? if(n_inliers_count > n_best_inliers_count) { n_best_inliers_count = n_inliers_count; // Save the current model/inlier/coefficients selection as being the best so far model_ = selection; model_coefficients_ = model_coefficients; // Compute the k parameter (k=log(z)/log(1-w^n)) double w = static_cast (n_best_inliers_count) / static_cast (sac_model_->getIndices()->size()); double p_no_outliers = 1.0 - pow(w, static_cast (selection.size())); p_no_outliers = (std::max) (std::numeric_limits::epsilon(), p_no_outliers); // Avoid division by -Inf p_no_outliers = (std::min) (1.0 - std::numeric_limits::epsilon(), p_no_outliers); // Avoid division by 0. k = log(1.0 - probability_) / log(p_no_outliers); } ++iterations_; if(debug_verbosity_level > 1) fprintf(stdout, "[sm::RandomSampleConsensus::computeModel] Trial %d out of %f: %d inliers (best is: %d so far).\n", iterations_, k, n_inliers_count, n_best_inliers_count ); if(iterations_ > max_iterations_) { if(debug_verbosity_level > 0) fprintf(stdout, "[sm::RandomSampleConsensus::computeModel] RANSAC reached the maximum number of trials.\n"); break; } } if(debug_verbosity_level > 0) fprintf(stdout, "[sm::RandomSampleConsensus::computeModel] Model: %zu size, %d inliers.\n", model_.size(), n_best_inliers_count ); if(model_.empty()) { inliers_.clear(); return (false); } // Get the set of inliers that correspond to the best model found so far sac_model_->selectWithinDistance( model_coefficients_, threshold_, inliers_ ); return (true); } opengv/include/opengv/sac/implementation/MultiRansac.hpp0000664016516101651610000001464213344612246022465 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS template opengv::sac::MultiRansac

::MultiRansac( int maxIterations, double threshold, double probability) : MultiSampleConsensus

(maxIterations, threshold, probability) {} template opengv::sac::MultiRansac

::~MultiRansac() {} template bool opengv::sac::MultiRansac::computeModel( int debug_verbosity_level ) { typedef PROBLEM_T problem_t; typedef typename problem_t::model_t model_t; iterations_ = 0; int n_best_inliers_count = -INT_MAX; double k = 1.0; std::vector > selection; model_t model_coefficients; int n_inliers_count = 0; unsigned skipped_count = 0; // supress infinite loops by just allowing 10 x maximum allowed iterations for // invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate while( iterations_ < k && skipped_count < max_skip ) { // Get X samples which satisfy the model criteria sac_model_->getSamples( iterations_, selection ); if( selection.empty() ) { fprintf( stderr, "[sm::RandomSampleConsensus::computeModel] No samples could be selected!\n" ); break; } // Search for inliers in the point cloud for the current plane model M if(!sac_model_->computeModelCoefficients( selection, model_coefficients )) { //++iterations_; ++ skipped_count; continue; } // Select the inliers that are within threshold_ from the model //sac_model_->selectWithinDistance(model_coefficients, threshold_, inliers); //if(inliers.empty() && k > 1.0) // continue; n_inliers_count = sac_model_->countWithinDistance( model_coefficients, threshold_ ); // Better match ? if( n_inliers_count > n_best_inliers_count ) { n_best_inliers_count = n_inliers_count; // Save the current model/inlier/coefficients selection as being the best so far model_ = selection; model_coefficients_ = model_coefficients; //MultiRansac preparation for probability computation std::shared_ptr > > multiIndices = sac_model_->getIndices(); size_t multiIndicesNumber = 0; for( size_t multiIter = 0; multiIter < multiIndices->size(); multiIter++ ) multiIndicesNumber += multiIndices->at(multiIter).size(); size_t multiSelectionSize = 0; for( size_t multiIter = 0; multiIter < selection.size(); multiIter++ ) multiSelectionSize += selection[multiIter].size(); // Compute the k parameter (k=log(z)/log(1-w^n)) double w = static_cast (n_best_inliers_count) / static_cast (multiIndicesNumber); double p_no_outliers = 1.0 - pow(w, static_cast (multiSelectionSize)); p_no_outliers = (std::max) (std::numeric_limits::epsilon(), p_no_outliers); // Avoid division by -Inf p_no_outliers = (std::min) (1.0 - std::numeric_limits::epsilon(), p_no_outliers); // Avoid division by 0. k = log(1.0 - probability_) / log(p_no_outliers); } ++iterations_; if(debug_verbosity_level > 1) fprintf(stdout, "[sm::RandomSampleConsensus::computeModel] Trial %d out of %f: %d inliers (best is: %d so far).\n", iterations_, k, n_inliers_count, n_best_inliers_count ); if(iterations_ > max_iterations_) { if(debug_verbosity_level > 0) fprintf(stdout, "[sm::RandomSampleConsensus::computeModel] RANSAC reached the maximum number of trials.\n"); break; } } if(debug_verbosity_level > 0) { size_t multiModelSize = 0; for( size_t modelIter = 0; modelIter < model_.size(); modelIter++ ) multiModelSize += model_[modelIter].size(); fprintf(stdout, "[sm::RandomSampleConsensus::computeModel] Model: %zu size, %d inliers.\n", multiModelSize, n_best_inliers_count ); } if(model_.empty()) { inliers_.clear(); return (false); } // Get the set of inliers that correspond to the best model found so far sac_model_->selectWithinDistance( model_coefficients_, threshold_, inliers_ ); return (true); } opengv/include/opengv/sac/implementation/Lmeds.hpp0000664016516101651610000001636013635643413021311 0ustar dimadima/****************************************************************************** * Authors: Johannes Mikulasch * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from PCL and from Ransac.hpp which has been derived from ROS template opengv::sac::Lmeds

::Lmeds( int maxIterations, double threshold, double probability) : SampleConsensus

(maxIterations, threshold, probability) {} template opengv::sac::Lmeds

::~Lmeds(){} template bool opengv::sac::Lmeds::computeModel(int debug_verbosity_level) { typedef PROBLEM_T problem_t; typedef typename problem_t::model_t model_t; // Warn and exit if no threshold was set if (threshold_ == std::numeric_limits::max()) { fprintf(stderr,"[sm::LeastMedianSquares::computeModel] No threshold set!\n"); return (false); } iterations_ = 0; double d_best_penalty = std::numeric_limits::max(); std::vector best_model; std::vector selection; model_t model_coefficients; std::vector distances; int n_inliers_count = 0; unsigned skipped_count = 0; // suppress infinite loops by just allowing 10 x maximum allowed iterations for // invalid model parameters! const unsigned max_skip = max_iterations_ * 10; if(debug_verbosity_level > 1) fprintf(stdout, "[sm::LeastMedianSquares::computeModel] Starting Least Median of Squares\n" "max_iterations: %d\n" "max_skip: %d\n", max_iterations_, max_skip); // Iterate while(iterations_ < max_iterations_ && skipped_count < max_skip) { // Get X samples which satisfy the model criteria sac_model_->getSamples(iterations_, selection); if(selection.empty()) { fprintf(stderr, "[sm::LeastMedianSquares::computeModel] No samples could be selected!\n"); break; } if(!sac_model_->computeModelCoefficients(selection, model_coefficients)) { ++ skipped_count; continue; } double d_cur_penalty = 0; // Iterate through the 3d points and calculate the distances from them to the model distances.clear(); sac_model_->getDistancesToModel(model_coefficients, distances); // No distances? The model must not respect the user given constraints if (distances.empty ()) { ++skipped_count; continue; } // Clip distances smaller than 0. Square the distances for (std::size_t i = 0; i < distances.size(); ++i) { if (distances[i] < 0) { distances[i] = 0; } distances[i] = distances[i] * distances[i]; } std::sort (distances.begin(), distances.end()); size_t mid = sac_model_->getIndices()->size() / 2; if (mid >= distances.size()) { ++skipped_count; continue; } // Do we have a "middle" point or should we "estimate" one ? if (sac_model_->getIndices()->size() % 2 == 0) { d_cur_penalty = (distances[mid-1] + distances[mid]) / 2; } else { d_cur_penalty = distances[mid]; } // Better match ? if(d_cur_penalty < d_best_penalty) { d_best_penalty = d_cur_penalty; // Save the current model/inlier/coefficients selection as being the best so far model_ = selection; model_coefficients_ = model_coefficients; } ++iterations_; if(debug_verbosity_level > 1) fprintf(stdout, "[sm::LeastMedianSquares::computeModel] Trial %d out of %d. Best penalty is: %f so far. Current penalty is: %f\n", iterations_, max_iterations_, d_best_penalty, d_cur_penalty); } if(model_.empty()) { if (debug_verbosity_level > 0) fprintf(stdout,"[sm::LeastMedianSquares::computeModel] Unable to find a solution!\n"); return (false); } // Classify the data points into inliers and outliers // Sigma = 1.4826 * (1 + 5 / (n-d)) * sqrt (M) // @note: See "Robust Regression Methods for Computer Vision: A Review" //double sigma = 1.4826 * (1 + 5 / (sac_model_->getIndices ()->size () - best_model.size ())) * sqrt (d_best_penalty); //double threshold = 2.5 * sigma; // Iterate through the 3d points and calculate the distances from them to the model again distances.clear(); sac_model_->getDistancesToModel(model_coefficients_, distances); // No distances? The model must not respect the user given constraints if (distances.empty()) { fprintf(stderr,"[sm::LeastMedianSquares::computeModel] The model found failed to verify against the given constraints!\n"); return (false); } std::vector &indices = *sac_model_->getIndices(); if (distances.size () != indices.size ()) { fprintf(stderr,"[sm::LeastMedianSquares::computeModel] Estimated distances (%zu) differs than the normal of indices (%zu).\n", distances.size (), indices.size ()); return false; } inliers_.resize(distances.size()); // Get the inliers for the best model found n_inliers_count = 0; for (size_t i = 0; i < distances.size(); ++i) if (distances[i] <= threshold_) inliers_[n_inliers_count++] = indices[i]; // Resize the inliers vector inliers_.resize(n_inliers_count); if (debug_verbosity_level > 0) fprintf(stdout,"[sm::LeastMedianSquares::computeModel] Model: %zu size, %d inliers.\n", model_.size (), n_inliers_count); return (true); } opengv/include/opengv/sac/implementation/MultiSampleConsensus.hpp0000664016516101651610000000520413344612246024372 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS template opengv::sac::MultiSampleConsensus

::MultiSampleConsensus( int maxIterations, double threshold, double probability) : max_iterations_(maxIterations), threshold_(threshold), probability_(probability) {} template opengv::sac::MultiSampleConsensus

::~MultiSampleConsensus() {} opengv/include/opengv/sac/implementation/SampleConsensus.hpp0000664016516101651610000000514713344612246023365 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS template opengv::sac::SampleConsensus

::SampleConsensus( int maxIterations, double threshold, double probability) : max_iterations_(maxIterations), threshold_(threshold), probability_(probability) {} template opengv::sac::SampleConsensus

::~SampleConsensus(){} opengv/include/opengv/sac/MultiSampleConsensusProblem.hpp0000664016516101651610000002313513344612246022671 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS /** * \file MultiSampleConsensusProblem.hpp * \brief Basis-class for Sample-consensus problems. Contains declarations for * the three basic functions of a sample-consensus problem (sample * drawing, computation of a hypothesis, and verification of a * hypothesis). This version is intended for use with the * RelativeMultiAdapterBase, and attempts to do sampling in multiple * camera-pairs in each hypothesis instantiation. */ #ifndef OPENGV_SAC_MULTISAMPLECONSENSUSPROBLEM_HPP_ #define OPENGV_SAC_MULTISAMPLECONSENSUSPROBLEM_HPP_ #include #include #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * Basis-class for Sample-consensus problems containing the three basic * functions for model-fitting. This one is using multi-indices for homogeneous * sampling over groups of samples. */ template class MultiSampleConsensusProblem { public: /** The model we are trying to fit */ typedef MODEL_T model_t; /** * \brief Contructor. * \param[in] randomSeed Setting the seed of the random number generator with * something unique, namely the current time. */ MultiSampleConsensusProblem( bool randomSeed = true ); /** * \brief Destructor. */ virtual ~MultiSampleConsensusProblem(); /** * \brief Get samples for hypothesis generation. * \param[in] iterations We won't try forever to get a good sample, this * parameter keeps track of the iterations. * \param[out] samples The multi-indices of the samples we attempt to use. */ virtual void getSamples( int &iterations, std::vector< std::vector > &samples ); /** * \brief Check if a set of samples for model generation is degenerate * \param[in] sample The multi-indices of the samples we attempt to use for * model instantiation. * \return Is this set of samples ok? */ virtual bool isSampleGood( const std::vector< std::vector > & sample ) const; /** * \brief Get a pointer to the vector of multi-indices used. * \return A pointer to the vector of multi-indices used. */ std::shared_ptr< std::vector< std::vector > > getIndices() const; /** * \brief Sub-function for getting samples for hypothesis generation. * \param[out] sample The multi-indices of the samples we attempt to use. */ void drawIndexSample( std::vector< std::vector > & sample ); /** * \brief Get the number of samples needed for a hypothesis generation. * Needs implementation in the child class. * \return The number of samples in each group needed for hypothesis generation. */ virtual std::vector getSampleSizes() const = 0; /** * \brief Compute a model from a set of samples. Needs implementation in the * child-class. * \param[in] indices The multi-indices of the samples we use for the hypothesis. * \param[out] outModel The computed model. * \return Success? */ virtual bool computeModelCoefficients( const std::vector< std::vector > & indices, model_t & outModel) const = 0; /** * \brief Refine the model coefficients over a given set (inliers). Needs * implementation in the child-class. * \param[in] inliers The multi-indices of the inlier samples supporting the model. * \param[in] model_coefficients The initial guess for the model coefficients. * \param[out] optimized_coefficients The resultant refined coefficients. */ virtual void optimizeModelCoefficients( const std::vector< std::vector > & inliers, const model_t & model_coefficients, model_t & optimized_coefficients ) = 0; /** * \brief Compute the distances of all samples whith respect to given model * coefficients. Needs implementation in the child-class. * \param[in] model The coefficients of the model hypothesis. * \param[in] indices The multi-indices of the samples of which we compute distances. * \param[out] scores The resultant distances of the selected samples. Low * distances mean a good fit. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector< std::vector > & indices, std::vector< std::vector > & scores ) const = 0; /** * \brief Compute the distances of all samples which respect to given model * coefficients. * \param[in] model_coefficients The coefficients of the model hypothesis. * \param[out] distances The resultant distances of all samples. Low distances * mean a good fit. */ virtual void getDistancesToModel( const model_t & model_coefficients, std::vector< std::vector > &distances ); /** * \brief Select all the inlier samples whith respect to given model * coefficients. * \param[in] model_coefficients The coefficients of the model hypothesis. * \param[in] threshold A maximum admissible distance threshold for * determining the inliers and outliers. * \param[out] inliers The resultant multi-indices of inlier samples. */ virtual void selectWithinDistance( const model_t &model_coefficients, const double threshold, std::vector< std::vector > &inliers ); /** * \brief Count all the inlier samples whith respect to given model * coefficients. * \param[in] model_coefficients The coefficients of the model hypothesis. * \param[in] threshold A maximum admissible distance threshold for * determining the inliers and outliers. * \return The resultant number of inliers */ virtual int countWithinDistance( const model_t &model_coefficients, const double threshold); /** * \brief Set the indices_ variable (see member-description). * \param[in] indices The multi-indices we want to use. */ void setIndices(const std::vector< std::vector > & indices); /** * \brief Use this method if you want to use all samples. * \param[in] N The number of samples in each group. */ void setUniformIndices(std::vector N); /** * \brief Get a random number. * \return A random number. */ int rnd(); /** The maximum number of times we try to extract a valid set of samples */ int max_sample_checks_; /** The multi-indices of the samples we are using for solving the entire * problem. These are not the multi-indices for generating a hypothesis, but * all indices for model verification */ std::shared_ptr< std::vector< std::vector > > indices_; /** A shuffled version of the multi-indices used for random sample drawing */ std::vector< std::vector > shuffled_indices_; /** \brief std-based random number generator algorithm. */ std::mt19937 rng_alg_; /** \brief std-based random number generator distribution. */ std::shared_ptr< std::uniform_int_distribution<> > rng_dist_; /** \brief std-based random number generator. */ std::shared_ptr< std::function > rng_gen_; }; } // namespace sac } // namespace opengv #include "implementation/MultiSampleConsensusProblem.hpp" #endif /* OPENGV_SAC_MULTISAMPLECONSENSUS_PROBLEM_HPP_ */ opengv/include/opengv/sac/SampleConsensusProblem.hpp0000664016516101651610000002173413344612246021661 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS /** * \file SampleConsensusProblem.hpp * \brief Basis-class for Sample-consensus problems. Contains declarations for * the three basic functions of a sample-consensus problem (sample * drawing, computation of a hypothesis, and verification of a * hypothesis). */ #ifndef OPENGV_SAC_SAMPLECONSENSUSPROBLEM_HPP_ #define OPENGV_SAC_SAMPLECONSENSUSPROBLEM_HPP_ #include #include #include #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * Basis-class for Sample-consensus problems containing the three basic * functions for model-fitting. */ template class SampleConsensusProblem { public: /** The model we are trying to fit */ typedef MODEL_T model_t; /** * \brief Contructor. * \param[in] randomSeed Setting the seed of the random number generator with * something unique, namely the current time. */ SampleConsensusProblem( bool randomSeed = true ); /** * \brief Destructor. */ virtual ~SampleConsensusProblem(); /** * \brief Get samples for hypothesis generation. * \param[in] iterations We won't try forever to get a good sample, this * parameter keeps track of the iterations. * \param[out] samples The indices of the samples we attempt to use. */ virtual void getSamples( int &iterations, std::vector &samples ); /** * \brief Check if a set of samples for model generation is degenerate * \param[in] sample The indices of the samples we attempt to use for * model instantiation. * \return Is this set of samples ok? */ virtual bool isSampleGood( const std::vector & sample ) const; /** * \brief Get a pointer to the vector of indices used. * \return A pointer to the vector of indices used. */ std::shared_ptr< std::vector > getIndices() const; /** * \brief Sub-function for getting samples for hypothesis generation. * \param[out] sample The indices of the samples we attempt to use. */ void drawIndexSample( std::vector & sample ); /** * \brief Get the number of samples needed for a hypothesis generation. * Needs implementation in the child class. * \return The number of samples needed for hypothesis generation. */ virtual int getSampleSize() const = 0; /** * \brief Compute a model from a set of samples. Needs implementation in the * child-class. * \param[in] indices The indices of the samples we use for the hypothesis. * \param[out] outModel The computed model. * \return Success? */ virtual bool computeModelCoefficients( const std::vector & indices, model_t & outModel) const = 0; /** * \brief Refine the model coefficients over a given set (inliers). Needs * implementation in the child-class. * \param[in] inliers The indices of the inlier samples supporting the model. * \param[in] model_coefficients The initial guess for the model coefficients. * \param[out] optimized_coefficients The resultant refined coefficients. */ virtual void optimizeModelCoefficients( const std::vector & inliers, const model_t & model_coefficients, model_t & optimized_coefficients ) = 0; /** * \brief Compute the distances of all samples whith respect to given model * coefficients. Needs implementation in the child-class. * \param[in] model The coefficients of the model hypothesis. * \param[in] indices The indices of the samples of which we compute distances. * \param[out] scores The resultant distances of the selected samples. Low * distances mean a good fit. */ virtual void getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores ) const = 0; /** * \brief Compute the distances of all samples which respect to given model * coefficients. * \param[in] model_coefficients The coefficients of the model hypothesis. * \param[out] distances The resultant distances of all samples. Low distances * mean a good fit. */ virtual void getDistancesToModel( const model_t & model_coefficients, std::vector &distances ); /** * \brief Select all the inlier samples whith respect to given model * coefficients. * \param[in] model_coefficients The coefficients of the model hypothesis. * \param[in] threshold A maximum admissible distance threshold for * determining the inliers and outliers. * \param[out] inliers The resultant indices of inlier samples. */ virtual void selectWithinDistance( const model_t &model_coefficients, const double threshold, std::vector &inliers ); /** * \brief Count all the inlier samples whith respect to given model * coefficients. * \param[in] model_coefficients The coefficients of the model hypothesis. * \param[in] threshold A maximum admissible distance threshold for * determining the inliers and outliers. * \return The resultant number of inliers */ virtual int countWithinDistance( const model_t &model_coefficients, const double threshold ); /** * \brief Set the indices_ variable (see member-description). * \param[in] indices The indices we want to use. */ void setIndices( const std::vector & indices ); /** * \brief Use this method if you want to use all samples. * \param[in] N The number of samples. */ void setUniformIndices( int N ); /** * \brief Get a random number. * \return A random number. */ int rnd(); /** The maximum number of times we try to extract a valid set of samples */ int max_sample_checks_; /** The indices of the samples we are using for solving the entire * problem. These are not the indices for generating a hypothesis, but * all indices for model verification */ std::shared_ptr< std::vector > indices_; /** A shuffled version of the indices used for random sample drawing */ std::vector shuffled_indices_; /** \brief std-based random number generator algorithm. */ std::mt19937 rng_alg_; /** \brief std-based random number generator distribution. */ std::shared_ptr< std::uniform_int_distribution<> > rng_dist_; /** \brief std-based random number generator. */ std::shared_ptr< std::function > rng_gen_; }; } // namespace sac } // namespace opengv #include "implementation/SampleConsensusProblem.hpp" #endif /* OPENGV_SAC_SAMPLECONSENSUSPROBLEM_HPP_ */ opengv/include/opengv/sac/Ransac.hpp0000664016516101651610000000745013344612246016424 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS /** * \file Ransac.hpp * \brief Implementation of the Ransac algorithm as outlined in [15]. */ #ifndef OPENGV_SAC_RANSAC_HPP_ #define OPENGV_SAC_RANSAC_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * The Ransac sample consensus method, as outlined in [15]. */ template class Ransac : public SampleConsensus { public: /** A child of SampleConsensusProblem */ typedef PROBLEM_T problem_t; /** The model we trying to fit */ typedef typename problem_t::model_t model_t; using SampleConsensus::max_iterations_; using SampleConsensus::threshold_; using SampleConsensus::iterations_; using SampleConsensus::sac_model_; using SampleConsensus::model_; using SampleConsensus::model_coefficients_; using SampleConsensus::inliers_; using SampleConsensus::probability_; /** * \brief Constructor. */ Ransac( int maxIterations = 1000, double threshold = 1.0, double probability = 0.99 ); /** * \brief Destructor. */ virtual ~Ransac(); /** * \brief Fit the model. */ bool computeModel( int debug_verbosity_level = 0 ); }; } // namespace sac } // namespace opengv #include "implementation/Ransac.hpp" #endif /* OPENGV_SAC_RANSAC_HPP_ */ opengv/include/opengv/sac/MultiRansac.hpp0000664016516101651610000001022413344612246017430 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS /** * \file MultiRansac.hpp * \brief Implementation of the Ransac algorithm as outlined in [15]. This * version is intended for use with the RelativeMultiAdapterBase, and * attempts to do sampling in multiple camera-pairs in each hypothesis * instantiation. */ #ifndef OPENGV_SAC_MULTIRANSAC_HPP_ #define OPENGV_SAC_MULTIRANSAC_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * The Ransac sample consensus method, as outlined in [15]. This one is using * multi-indices for homogeneous sampling over groups of samples. */ template class MultiRansac : public MultiSampleConsensus { public: /** A child of MultiSampleConsensusProblem */ typedef PROBLEM_T problem_t; /** The model we trying to fit */ typedef typename problem_t::model_t model_t; using MultiSampleConsensus::max_iterations_; using MultiSampleConsensus::threshold_; using MultiSampleConsensus::iterations_; using MultiSampleConsensus::sac_model_; using MultiSampleConsensus::model_; using MultiSampleConsensus::model_coefficients_; using MultiSampleConsensus::inliers_; using MultiSampleConsensus::probability_; /** * \brief Constructor. */ MultiRansac( int maxIterations = 1000, double threshold = 1.0, double probability = 0.99 ); /** * \brief Destructor. */ virtual ~MultiRansac(); /** * \brief Fit the model. */ bool computeModel( int debug_verbosity_level = 0 ); }; } // namespace sac } // namespace opengv #include "implementation/MultiRansac.hpp" #endif /* OPENGV_SAC_MULTIRANSAC_HPP_ */ opengv/include/opengv/sac/Lmeds.hpp0000664016516101651610000000733713635643413016270 0ustar dimadima/****************************************************************************** * Authors: Johannes Mikulasch * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from Ransac which has been derived from ROS /** * \file Lmeds.hpp * \brief Implementation of the Lmeds algorithm */ #ifndef OPENGV_SAC_LMEDS_HPP_ #define OPENGV_SAC_LMEDS_HPP_ #include #include #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * The LMedS (Least Median of Squares) sample consensus method */ template class Lmeds : public SampleConsensus { public: /** A child of SampleConsensusProblem */ typedef PROBLEM_T problem_t; /** The model we trying to fit */ typedef typename problem_t::model_t model_t; using SampleConsensus::max_iterations_; using SampleConsensus::threshold_; using SampleConsensus::iterations_; using SampleConsensus::sac_model_; using SampleConsensus::model_; using SampleConsensus::model_coefficients_; using SampleConsensus::inliers_; using SampleConsensus::probability_; /** * \brief Constructor. */ Lmeds( int maxIterations = 1000, double threshold = 1.0, double probability = 0.99); /** * \brief Destructor. */ virtual ~Lmeds(); /** * \brief Fit the model. */ bool computeModel( int debug_verbosity_level = 0 ); }; } // namespace sac } // namespace opengv #include "implementation/Lmeds.hpp" #endif /* OPENGV_SAC_LMEDS_HPP_ */ opengv/include/opengv/sac/MultiSampleConsensus.hpp0000664016516101651610000001202213344612246021341 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS /** * \file MultiSampleConsensus.hpp * \brief This is a base class for sample consensus methods such as Ransac. * Derivatives call the three basic functions of a sample-consensus * problem (sample drawing, computation of a hypothesis, and verification * of a hypothesis). This version is intended for use with the * RelativeMultiAdapterBase, and attempts to do sampling in multiple * camera-pairs in each hypothesis instantiation. */ #ifndef OPENGV_SAC_MULTISAMPLECONSENSUS_HPP_ #define OPENGV_SAC_MULTISAMPLECONSENSUS_HPP_ /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * Super-class for sample consensus methods, such as Ransac. This one is using * multi-indices for homogeneous sampling over groups of samples. */ template class MultiSampleConsensus { public: /** A child of MultiSampleConsensusProblem */ typedef PROBLEM_T problem_t; /** The model we trying to fit */ typedef typename problem_t::model_t model_t; /** * \brief Constructor. * \param[in] maxIterations The maximum number of hypothesis generations * \param[in] threshold Some threshold value for classifying samples as * an inlier or an outlier. * \param[in] probability The probability of being able to draw at least one * sample that is free of outliers (see [15]) */ MultiSampleConsensus( int maxIterations = 1000, double threshold = 1.0, double probability = 0.99 ); /** * \brief Destructor */ virtual ~MultiSampleConsensus(); /** * \brief Fit the model to the data. * \param[in] debug_verbosity_level Sets the verbosity level. * \return bool True if success. */ virtual bool computeModel( int debug_verbosity_level = 0 ) = 0; // \todo accessors //private: /** the maximum number of iterations */ int max_iterations_; /** the current number of iterations */ int iterations_; /** the threshold for classifying inliers */ double threshold_; /** the current probability (defines remaining iterations) */ double probability_; /** the currently best model coefficients */ model_t model_coefficients_; /** the group-wise indices for the currently best hypothesis */ std::vector< std::vector > model_; /** the group-wise indices of the samples that have been clasified as inliers */ std::vector< std::vector > inliers_; /** the multi-sample-consensus problem we are trying to solve */ std::shared_ptr sac_model_; }; } // namespace sac } // namespace opengv #include "implementation/MultiSampleConsensus.hpp" #endif /* OPENGV_MULTISAMPLECONSENSUS_HPP_ */ opengv/include/opengv/sac/SampleConsensus.hpp0000664016516101651610000001135413344612246020335 0ustar dimadima/****************************************************************************** * Authors: Laurent Kneip & Paul Furgale * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ //Note: has been derived from ROS /** * \file SampleConsensus.hpp * \brief This is a base class for sample consensus methods such as Ransac. * Derivatives call the three basic functions of a sample-consensus * problem (sample drawing, computation of a hypothesis, and verification * of a hypothesis). */ #ifndef OPENGV_SAC_SAMPLECONSENSUS_HPP_ #define OPENGV_SAC_SAMPLECONSENSUS_HPP_ #include /** * \brief The namespace of this library. */ namespace opengv { /** * \brief The namespace for the sample consensus methods. */ namespace sac { /** * Super-class for sample consensus methods, such as Ransac. */ template class SampleConsensus { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW /** A child of SampleConsensusProblem */ typedef PROBLEM_T problem_t; /** The model we trying to fit */ typedef typename problem_t::model_t model_t; /** * \brief Constructor. * \param[in] maxIterations The maximum number of hypothesis generations * \param[in] threshold Some threshold value for classifying samples as * an inlier or an outlier. * \param[in] probability The probability of being able to draw at least one * sample that is free of outliers (see [15]) */ SampleConsensus( int maxIterations = 1000, double threshold = 1.0, double probability = 0.99 ); /** * \brief Destructor */ virtual ~SampleConsensus(); /** * \brief Fit the model to the data. * \param[in] debug_verbosity_level Sets the verbosity level. * \return bool True if success. */ virtual bool computeModel( int debug_verbosity_level = 0 ) = 0; // \todo accessors //private: /** the maximum number of iterations */ int max_iterations_; /** the current number of iterations */ int iterations_; /** the threshold for classifying inliers */ double threshold_; /** the current probability (defines remaining iterations) */ double probability_; /** the currently best model coefficients */ model_t model_coefficients_; /** the indices for the currently best hypothesis */ std::vector model_; /** the indices of the samples that have been clasified as inliers */ std::vector inliers_; /** the sample-consensus problem we are trying to solve */ std::shared_ptr sac_model_; }; } // namespace sac } // namespace opengv #include "implementation/SampleConsensus.hpp" #endif /* OPENGV_SAC_SAMPLECONSENSUS_HPP_ */ opengv/README.txt0000644016516101651610000000144414257362435012514 0ustar dimadimalibrary: OpenGV pages: http://laurentkneip.github.io/opengv brief: OpenGV is a collection of computer vision methods for solving geometric vision problems. It contains absolute-pose, relative-pose, triangulation, and point-cloud alignment methods for the calibrated case. All problems can be solved with central or non-central cameras, and embedded into a random sample consensus or nonlinear optimization context. Matlab and Python interfaces are implemented as well. The link to the above pages also shows links to precompiled Matlab mex-libraries. Please consult the documentation for more information. author: Laurent Kneip, ShanghaiTech, Mobile Perception Lab (http://mpl.sist.shanghaitech.edu.cn) contact: kneip.laurent@gmail.com opengv/.gitignore0000664016516101651610000000004113635643413012775 0ustar dimadimalib build *.mexa64 *.pyc .vscode opengv/.travis.yml0000664016516101651610000000261613635643413013130 0ustar dimadimadist: trusty sudo: false language: cpp compiler: - clang - gcc cache: apt: true addons: apt: packages: - build-essential - python-dev - libboost-python-dev - python-numpy-dev - libeigen3-dev env: global: # CMAKE minimal required version 3.1.0 - CMAKE_URL="https://cmake.org/files/v3.1/cmake-3.1.3-Linux-x86_64.tar.gz" - CMAKE_ROOT=${TRAVIS_BUILD_DIR}/cmake - CMAKE_SOURCE=${CMAKE_ROOT}/source - CMAKE_INSTALL=${CMAKE_ROOT}/install before_install: # CMAKE most recent version - > if [ "$(ls -A ${CMAKE_INSTALL})" ]; then echo "CMake found in cache."; ls -A ${CMAKE_INSTALL} export PATH=${CMAKE_INSTALL}/bin:${PATH}; cmake --version else mkdir --parent ${CMAKE_SOURCE} mkdir --parent ${CMAKE_INSTALL} ls -A ${CMAKE_INSTALL} travis_retry wget --no-check-certificate --quiet -O - ${CMAKE_URL} | tar --strip-components=1 -xz -C ${CMAKE_INSTALL} export PATH=${CMAKE_INSTALL}/bin:${PATH}; cmake --version fi before_script: - mkdir build - cd build - > if [ $CXX = "clang++" ]; then cmake .. -DBUILD_TESTS:BOOL=ON -DBUILD_PYTHON:BOOL=ON -DCMAKE_CXX_FLAGS="-Wno-deprecated-register" else cmake .. -DBUILD_TESTS:BOOL=ON -DBUILD_PYTHON:BOOL=ON fi script: - make -j2 VERBOSE=1 - make test cache: directories: - $CMAKE_INSTALL opengv/matlab/0000775016516101651610000000000013635643413012252 5ustar dimadimaopengv/matlab/ransac_test.m0000664016516101651610000000062513344612246014736 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); % central case -> only one camera cam_number = 1; % let's only get 6 points, and generate new ones in each iteration pt_number = 100; % noise test, so no outliers outlier_fraction = 0.1; noise = 0.0; [points,v,t,R] = create2D3DExperiment(pt_number,cam_number,noise,outlier_fraction); [X, inliers] = opengv('p3p_kneip_ransac',points,v);opengv/matlab/opengv.cpp0000664016516101651610000015514513635643413014267 0ustar dimadimastatic const char *copyright = " Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved."; /****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ // Matlab usage: // // X = opengv ( method, data1, data2 ) // X = opengv ( method, indices, data1, data2 ) // X = opengv ( method, indices, data1, data2, prior ) // // where // method is a string that characterizes the algorithm to use // data1, data2 are matched points (each one of dimension 3xn or 6xn) // indices is a vector of indices indicating a subset of the correspondences // X is a 3xnxm matrix, where n is the second dimensionality of the solution space, // and m is the number of solutions // prior is a prior pose in case it is known (a matrix of format [R t]) // // Note that the indices of inliers can also be returned for Ransac methods // if adding a second left-hand side parameter upon function call // (format: [X, inliers] = opengv(...) ) //matlab header //standard headers #include #include #include #include "mex.h" //include generic headers for opengv stuff #include //include the matlab-adapters #include #include #include #include #include //expose all methods to matlab #include #include #include //expose all ransac-facilities to matlab #include #include #include #include #include #include #include // The different methods that can be used within Matlab static const char* methods[]= { // absolute_pose methods "p2p", // 3 "p3p_kneip", // 9 "p3p_gao", // 7 "epnp", // 4 "p3p_kneip_ransac", // 16 "p3p_gao_ransac", // 14 "epnp_ransac", // 11 "abs_nonlin_central", // 18 "gp3p", // 4 "gp3p_ransac", // 11 "gpnp", // 4 "abs_nonlin_noncentral", // 21 "upnp", // 4 // relative_pose methods "twopt", // 5 "twopt_rotationOnly", // 18 "rotationOnly", // 12 "fivept_stewenius", // 16 "fivept_nister", // 13 "fivept_kneip", // 12 "sevenpt", // 7 "eightpt", // 7 "eigensolver", // 11 "rotationOnly_ransac", // 19 "fivept_stewenius_ransac", // 23 "fivept_nister_ransac", // 20 "sevenpt_ransac", // 14 "eightpt_ransac", // 14 "eigensolver_ransac", // 18 "rel_nonlin_central", // 18 "sixpt", // 5 "seventeenpt", // 11 "ge", // 2 "sixpt_ransac", // 12 "seventeenpt_ransac", // 18 "ge_ransac", // 9 "rel_nonlin_noncentral", // 21 // point_cloud methods "threept_arun", // 12 "threept_arun_ransac" // 19 }; // The length of the method strings (needed for comparison) static const int methodsLengths[] = { 3,9,7,4,16,14,11,18,4,11,4,21,4,5,18,12,16,13,12, 7,7,11,19,23,20,14,14,18,18,5,11,2,12,18,9,21,12,19 }; static const int absCentralFirst = 0; static const int absCentralLast = 7; static const int absNoncentralFirst = 8; static const int absNoncentralLast = 11; static const int upnpIndex = 12; static const int relCentralFirst = 13; static const int relCentralLast = 28; static const int relNoncentralFirst = 29; static const int relNoncentralLast = 35; static const int pointCloudFirst = 36; static const int pointCloudLast = 37; // The number of methods (needed for comparison) static const int numberMethods = pointCloudLast + 1; enum Method { P2P, P3P_KNEIP, P3P_GAO, EPNP, P3P_KNEIP_RANSAC, P3P_GAO_RANSAC, EPNP_RANSAC, ABS_NONLIN_CENTRAL, GP3P, GP3P_RANSAC, GPNP, ABS_NONLIN_NONCENTRAL, UPNP, TWOPT, TWOPT_ROTATIONONLY, ROTATIONONLY, FIVEPT_STEWENIUS, FIVEPT_NISTER, FIVEPT_KNEIP, SEVENPT, EIGHTPT, EIGENSOLVER, ROTATIONONLY_RANSAC, FIVEPT_STEWENIUS_RANSAC, FIVEPT_NISTER_RANSAC, SEVENPT_RANSAC, EIGHTPT_RANSAC, EIGENSOLVER_RANSAC, REL_NONLIN_CENTRAL, SIXPT, SEVENTEENPT, GE, SIXPT_RANSAC, SEVENTEENPT_RANSAC, GE_RANSAC, REL_NONLIN_NONCENTRAL, THREEPT_ARUN, THREEPT_ARUN_RANSAC }; // Finds the method based on string comparison int findCase( const char* input, int inputLength ) { int n = 0; while( n < numberMethods ) { // First check the length of the string, it needs to be same if( inputLength == methodsLengths[n]) { // Now check if all the elements are the same int allSame = 1; for( int i = 0; i < inputLength; i++ ) { if( input[i] != methods[n][i] ) { allSame = 0; break; } } // Break if method found if( allSame ) return n; //Otherwise go on with the next one } n++; } // Return -1 if not found return -1; } // Print all possible cases void printCases() { mexPrintf("The known methods are:"); for( int i = 0; i < numberMethods; i++ ) { mexPrintf("\n"); mexPrintf(methods[i]); } mexPrintf("\n"); } typedef opengv::sac_problems::absolute_pose::AbsolutePoseSacProblem absRansac; typedef std::shared_ptr absRansacPtr; typedef opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem relRansac; typedef std::shared_ptr relRansacPtr; typedef opengv::sac_problems::relative_pose::NoncentralRelativePoseSacProblem nrelRansac; typedef std::shared_ptr nrelRansacPtr; typedef opengv::sac_problems::relative_pose::RotationOnlySacProblem rotRansac; typedef std::shared_ptr rotRansacPtr; typedef opengv::sac_problems::relative_pose::EigensolverSacProblem eigRansac; typedef std::shared_ptr eigRansacPtr; typedef opengv::sac_problems::point_cloud::PointCloudSacProblem ptRansac; typedef std::shared_ptr ptRansacPtr; // The main mex-function void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] ) { // Check if right number of arguments if( nrhs < 3 || nrhs > 5 ) { mexPrintf("opengv: Not an acceptable number of arguments\n"); mexPrintf("Usage: X = opengv( method, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2, prior )\n"); return; } // Get the method if( mxGetM(prhs[0]) != 1 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Usage: X = opengv( method, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2, prior )\n"); mexPrintf("Hint: Method must be a string\n"); return; } // Now get the string and find the caseNumber mwSize strlen = (mwSize) mxGetN(prhs[0]) + 1; char * method = (char *) malloc(strlen); mxGetString(prhs[0], method, strlen); int caseNumber = findCase(method, (int) mxGetN(prhs[0])); // Return if method not found if( caseNumber < 0 ) { mexPrintf("opengv: Unknown method\n"); printCases(); return; } // Characterize the type of the call int callCharacter = -1; const mxArray *data1; const mxArray *data2; const mwSize *data1dim; const mwSize *data2dim; if( nrhs == 3 ) // X = opengv( method, data1, data2 ) { // Check the input data1 = prhs[1]; data2 = prhs[2]; // Check the dimensions of the arguments int ndimensions1 = mxGetNumberOfDimensions(data1); int ndimensions2 = mxGetNumberOfDimensions(data2); data1dim = mxGetDimensions(data1); data2dim = mxGetDimensions(data2); // Now check them if( ndimensions1 != 2 || ndimensions2 != 2 || (data1dim[0] != 3 && data1dim[0] != 6) || (data2dim[0] != 3 && data2dim[0] != 6) || data1dim[1] != data2dim[1] || data1dim[1] < 1 || data2dim[1] < 1 ) { mexPrintf("opengv: Bad input to mex function\n"); mexPrintf("Assuming signature: X = opengv( method, data1, data2 )\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) or (6,n),\n"); mexPrintf("where n is the number of correspondences\n"); return; } callCharacter = 0; } if( nrhs == 4 ) { // X = opengv( method, indices, data1, data2 ) // Check the input data1 = prhs[2]; data2 = prhs[3]; // Check the dimensions of the arguments int ndimensions1 = mxGetNumberOfDimensions(data1); int ndimensions2 = mxGetNumberOfDimensions(data2); int ndimensions3 = mxGetNumberOfDimensions(prhs[1]); data1dim = mxGetDimensions(data1); data2dim = mxGetDimensions(data2); const mwSize *indicesDim = mxGetDimensions(prhs[1]); // Now check them if( ndimensions1 != 2 || ndimensions2 != 2 || ndimensions3 != 2 || (data1dim[0] != 3 && data1dim[0] != 6) || (data2dim[0] != 3 && data2dim[0] != 6) || indicesDim[0] != 1 || data1dim[1] != data2dim[1] || data1dim[1] < 1 || data2dim[1] < 1 || data2dim[1] < indicesDim[1] ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming signature: X = opengv( method, indices, data1, "); mexPrintf("data2 )\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) or (6,n),\n"); mexPrintf("where n is the number of correspondences\n"); mexPrintf("indices must be a 1xm vector, with m smaller or equal than n\n"); return; } callCharacter = 1; } if(nrhs == 5) { // X = opengv( method, indices, data1, data2, prior ) // Check the input data1 = prhs[2]; data2 = prhs[3]; // Check the dimensions of the arguments int ndimensions1 = mxGetNumberOfDimensions(data1); int ndimensions2 = mxGetNumberOfDimensions(data2); int ndimensions3 = mxGetNumberOfDimensions(prhs[1]); int ndimensions4 = mxGetNumberOfDimensions(prhs[4]); data1dim = mxGetDimensions(data1); data2dim = mxGetDimensions(data2); const mwSize *indicesDim = mxGetDimensions(prhs[1]); const mwSize *priorDim = mxGetDimensions(prhs[4]); // Now check them if( ndimensions1 != 2 || ndimensions2 != 2 || ndimensions3 != 2 || ndimensions4 != 2 || (data1dim[0] != 3 && data1dim[0] != 6) || (data2dim[0] != 3 && data2dim[0] != 6) || indicesDim[0] != 1 || priorDim[0] != 3 || (priorDim[1] != 1 && priorDim[1] != 3 && priorDim[1] != 4) || data1dim[1] != data2dim[1] || data1dim[1] < 1 || data2dim[1] < 1 || data2dim[1] < indicesDim[1] ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming signature: X = opengv( method, indices, data1, "); mexPrintf("data2, prior )\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) or (6,n),\n"); mexPrintf("where n is the number of correspondences\n"); mexPrintf("indices must be a 1xm vector, with m smaller or equal than n\n"); mexPrintf("prior must be a 3x1, 3x3, or 3x4 matrix\n"); return; } callCharacter = 2; } //create three pointers to absolute, relative, and point_cloud adapters here opengv::absolute_pose::AbsoluteAdapterBase* absoluteAdapter; opengv::relative_pose::RelativeAdapterBase* relativeAdapter; opengv::point_cloud::PointCloudAdapterBase* pointCloudAdapter; int translationPrior = 0; int rotationPrior = 0; opengv::translation_t translation; opengv::rotation_t rotation; //set the prior if needed if( callCharacter == 2 ) { const mxArray *prior; const mwSize *priorDim; prior = prhs[4]; priorDim = mxGetDimensions(prhs[4]); if( priorDim[1] == 1 ) { //set translation translationPrior = 1; double * ptr = (double*) mxGetData(prior); translation[0] = ptr[0]; translation[1] = ptr[1]; translation[2] = ptr[2]; } if( priorDim[1] == 3 ) { //set rotation rotationPrior = 1; double * ptr = (double*) mxGetData(prior); rotation(0,0) = ptr[0]; rotation(1,0) = ptr[1]; rotation(2,0) = ptr[2]; rotation(0,1) = ptr[3]; rotation(1,1) = ptr[4]; rotation(2,1) = ptr[5]; rotation(0,2) = ptr[6]; rotation(1,2) = ptr[7]; rotation(2,2) = ptr[8]; } if( priorDim[1] == 4 ) { translationPrior = 1; rotationPrior = 1; double * ptr = (double*) mxGetData(prior); rotation(0,0) = ptr[0]; rotation(1,0) = ptr[1]; rotation(2,0) = ptr[2]; rotation(0,1) = ptr[3]; rotation(1,1) = ptr[4]; rotation(2,1) = ptr[5]; rotation(0,2) = ptr[6]; rotation(1,2) = ptr[7]; rotation(2,2) = ptr[8]; translation[0] = ptr[9]; translation[1] = ptr[10]; translation[2] = ptr[11]; } } if( caseNumber >= absCentralFirst && caseNumber <= absCentralLast ) { //central absolute case if( data1dim[0] != 3 || data2dim[0] != 3 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) for a central "); mexPrintf("absolute method\n"); return; } absoluteAdapter = new opengv::absolute_pose::MACentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) absoluteAdapter->sett(translation); if( rotationPrior == 1 ) absoluteAdapter->setR(rotation); } if( caseNumber >= absNoncentralFirst && caseNumber <= absNoncentralLast ) { //non-central absolute case if( data1dim[0] != 3 || data2dim[0] != 6 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have sizes (3,n) and (6,n) for "); mexPrintf("a noncentral absolute method\n"); return; } absoluteAdapter = new opengv::absolute_pose::MANoncentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) absoluteAdapter->sett(translation); if( rotationPrior == 1 ) absoluteAdapter->setR(rotation); } if( caseNumber == upnpIndex ) { if( data1dim[0] != 3 || (data2dim[0] != 3 && data2dim[0] != 6) ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have sizes (3,n) and (3,n) or (6,n) for "); mexPrintf("upnp\n"); return; } if( data2dim[0] == 3 ) { absoluteAdapter = new opengv::absolute_pose::MACentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); } else { absoluteAdapter = new opengv::absolute_pose::MANoncentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); } if( translationPrior == 1 ) absoluteAdapter->sett(translation); if( rotationPrior == 1 ) absoluteAdapter->setR(rotation); } if( caseNumber >= relCentralFirst && caseNumber <= relCentralLast ) { //central relative case if( data1dim[0] != 3 || data2dim[0] != 3 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) for a central "); mexPrintf("relative method\n"); return; } relativeAdapter = new opengv::relative_pose::MACentralRelative( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) relativeAdapter->sett12(translation); if( rotationPrior == 1 ) relativeAdapter->setR12(rotation); } if(caseNumber >= relNoncentralFirst && caseNumber <= relNoncentralLast ) { //noncentral relative case if( data1dim[0] != 6 || data2dim[0] != 6 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (6,n) for a "); mexPrintf("noncentral relative method\n"); return; } relativeAdapter = new opengv::relative_pose::MANoncentralRelative( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) relativeAdapter->sett12(translation); if( rotationPrior == 1 ) relativeAdapter->setR12(rotation); } if(caseNumber >= pointCloudFirst && caseNumber <= pointCloudLast ) { //point-cloud case if( data1dim[0] != 3 || data2dim[0] != 3 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) for a "); mexPrintf("point-cloud method\n"); return; } pointCloudAdapter = new opengv::point_cloud::MAPointCloud( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) pointCloudAdapter->sett12(translation); if( rotationPrior == 1 ) pointCloudAdapter->setR12(rotation); } //check if a return argument is needed, otherwise we won't start computing if( nlhs != 1 && nlhs != 2 ) { if( nlhs > 2 ) mexPrintf("opengv: Returns one or two variables!\n"); return; } //create the indices array (todo: check if there is a smarter way for doing this) std::vector indices; int useIndices = 0; if( callCharacter > 0 ) { useIndices = 1; const mwSize *indicesDim = mxGetDimensions(prhs[1]); int numberOfIndices = indicesDim[1]; indices.reserve(numberOfIndices); double * mxIndices = (double*) mxGetData(prhs[1]); for( int i = 0; i < numberOfIndices; i++ ) indices.push_back(floor(mxIndices[i]+0.01)-1); } Method methodEnum = static_cast(caseNumber); if( caseNumber != (int) methodEnum ) { mexPrintf("opengv: This method is not yet implemented!\n"); return; } // Finally, call the respective algorithm switch (methodEnum) { case P2P: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::translation_t temp; if(useIndices) temp = opengv::absolute_pose::p2p(*absoluteAdapter,indices); else temp = opengv::absolute_pose::p2p(*absoluteAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 1; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 3*sizeof(double)); break; } case P3P_KNEIP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; if(useIndices) temp = opengv::absolute_pose::p3p_kneip(*absoluteAdapter,indices); else temp = opengv::absolute_pose::p3p_kneip(*absoluteAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case P3P_GAO: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; if(useIndices) temp = opengv::absolute_pose::p3p_gao(*absoluteAdapter,indices); else temp = opengv::absolute_pose::p3p_gao(*absoluteAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case EPNP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::absolute_pose::epnp(*absoluteAdapter,indices); else temp = opengv::absolute_pose::epnp(*absoluteAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case P3P_KNEIP_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::KNEIP, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::KNEIP ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case P3P_GAO_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GAO, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GAO ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case EPNP_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::EPNP, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::EPNP ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case ABS_NONLIN_CENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter,indices); else temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case GP3P: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; if(useIndices) temp = opengv::absolute_pose::gp3p(*absoluteAdapter,indices); else temp = opengv::absolute_pose::gp3p(*absoluteAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case GP3P_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GP3P, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GP3P ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case GPNP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::absolute_pose::gpnp(*absoluteAdapter,indices); else temp = opengv::absolute_pose::gpnp(*absoluteAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case ABS_NONLIN_NONCENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter,indices); else temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case UPNP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; if(useIndices) temp = opengv::absolute_pose::upnp(*absoluteAdapter,indices); else temp = opengv::absolute_pose::upnp(*absoluteAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case TWOPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::translation_t temp; if(useIndices) temp = opengv::relative_pose::twopt(*relativeAdapter,false,indices); else temp = opengv::relative_pose::twopt(*relativeAdapter,false); mwSize dims[2]; dims[0] = 3; dims[1] = 1; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 3*sizeof(double)); break; } case TWOPT_ROTATIONONLY: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; if(useIndices) temp = opengv::relative_pose::twopt_rotationOnly(*relativeAdapter,indices); else temp = opengv::relative_pose::twopt_rotationOnly(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case ROTATIONONLY: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; if(useIndices) temp = opengv::relative_pose::rotationOnly(*relativeAdapter,indices); else temp = opengv::relative_pose::rotationOnly(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case FIVEPT_STEWENIUS: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::complexEssentials_t temp2; if(useIndices) temp2 = opengv::relative_pose::fivept_stewenius(*relativeAdapter,indices); else temp2 = opengv::relative_pose::fivept_stewenius(*relativeAdapter); opengv::essentials_t temp; for(size_t i = 0; i < temp2.size(); i++) { opengv::essential_t essentialMatrix; for(size_t r = 0; r < 3; r++) { for(size_t c = 0; c < 3; c++) essentialMatrix(r,c) = temp2[i](r,c).real(); } temp.push_back(essentialMatrix); } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case FIVEPT_NISTER: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::essentials_t temp; if(useIndices) temp = opengv::relative_pose::fivept_nister(*relativeAdapter,indices); else temp = opengv::relative_pose::fivept_nister(*relativeAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case FIVEPT_KNEIP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotations_t temp; if(useIndices) temp = opengv::relative_pose::fivept_kneip(*relativeAdapter,indices); else { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("You must provide an indices vector\n"); break; } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case SEVENPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::essentials_t temp; if(useIndices) temp = opengv::relative_pose::sevenpt(*relativeAdapter,indices); else temp = opengv::relative_pose::sevenpt(*relativeAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case EIGHTPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::essential_t temp; if(useIndices) temp = opengv::relative_pose::eightpt(*relativeAdapter,indices); else temp = opengv::relative_pose::eightpt(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case EIGENSOLVER: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; if(useIndices) temp = opengv::relative_pose::eigensolver(*relativeAdapter,indices); else temp = opengv::relative_pose::eigensolver(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case ROTATIONONLY_RANSAC: { rotRansacPtr problem; if(useIndices) problem = rotRansacPtr( new rotRansac( *relativeAdapter, indices ) ); else problem = rotRansacPtr( new rotRansac( *relativeAdapter ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 9*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case FIVEPT_STEWENIUS_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::STEWENIUS, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::STEWENIUS ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); opengv::transformation_t optimizedModel; problem->optimizeModelCoefficients(ransac.inliers_,ransac.model_coefficients_,optimizedModel); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); //memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); memcpy(mxGetData(plhs[0]), optimizedModel.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case FIVEPT_NISTER_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::NISTER, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::NISTER ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case SEVENPT_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::SEVENPT, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::SEVENPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case EIGHTPT_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::EIGHTPT, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::EIGHTPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case EIGENSOLVER_RANSAC: { eigRansacPtr problem; if(useIndices) problem = eigRansacPtr( new eigRansac( *relativeAdapter, 10, indices ) ); else problem = eigRansacPtr( new eigRansac( *relativeAdapter, 10 ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0; ransac.max_iterations_ = 50; ransac.computeModel(); opengv::transformation_t temp; temp.block<3,3>(0,0) = ransac.model_coefficients_.rotation; temp.block<3,1>(0,3) = ransac.model_coefficients_.translation; mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case REL_NONLIN_CENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter,indices); else temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case SIXPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotations_t temp; if(useIndices) temp = opengv::relative_pose::sixpt(*relativeAdapter,indices); else temp = opengv::relative_pose::sixpt(*relativeAdapter); mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case SEVENTEENPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::relative_pose::seventeenpt(*relativeAdapter,indices); else temp = opengv::relative_pose::seventeenpt(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case GE: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; opengv::geOutput_t output; output.rotation = relativeAdapter->getR12(); if(useIndices) temp = opengv::relative_pose::ge(*relativeAdapter,indices,output); else temp = opengv::relative_pose::ge(*relativeAdapter,output); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]),temp.data(), 9*sizeof(double)); break; } case SIXPT_RANSAC: { nrelRansacPtr problem; if(useIndices) problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SIXPT, indices ) ); else problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SIXPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case SEVENTEENPT_RANSAC: { nrelRansacPtr problem; if(useIndices) problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SEVENTEENPT, indices ) ); else problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SEVENTEENPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case GE_RANSAC: { nrelRansacPtr problem; if(useIndices) problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::GE, indices ) ); else problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::GE ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case REL_NONLIN_NONCENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter,indices); else temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case THREEPT_ARUN: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; if(useIndices) temp = opengv::point_cloud::threept_arun(*pointCloudAdapter,indices); else temp = opengv::point_cloud::threept_arun(*pointCloudAdapter); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case THREEPT_ARUN_RANSAC: { ptRansacPtr problem; if(useIndices) problem = ptRansacPtr( new ptRansac( *pointCloudAdapter, indices ) ); else problem = ptRansacPtr( new ptRansac( *pointCloudAdapter ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 0.1; ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } default: //-1 { // impossible break; } } } opengv/matlab/benchmark_absolute_pose_noncentral_execution_timing.m0000664016516101651610000000307613344612246025166 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 4; % let's only get 6 points, and generate new ones in each iteration pt_number = 50; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 iterations iterations = 1000; % The algorithms we want to test algorithms = { 'gp3p'; 'gpnp'; 'upnp'}; % This defines the number of points used for every algorithm indices = { [1, 2, 3]; [1:1:50]; [1:1:50] }; % The name of the algorithms on the plots names = { 'GP3P'; 'GPnP (50pts)'; 'UPnP (50pts)' }; % The noise in this experiment noise = 1.0; %% Run the benchmark %prepare the overall result arrays num_algorithms = size(algorithms,1); execution_times = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [points,v,t,R] = create2D3DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; for a=1:num_algorithms tic T = opengv_donotuse(algorithms{a},indices{a},points,v,T_perturbed); execution_times(a,i) = toc/20.0; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %% Plot the results hist(execution_times') legend(names,'Location','NorthWest') xlabel('execution times [s]') grid on mean(execution_times') opengv/matlab/plot_expected_iterations.m0000664016516101651610000000272513344612246017533 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % The algorithms we want to test algorithms = [ 6; 8; 17 ]; % The name of the algorithms in the final plots names = { '6pt'; 'ge (8pt)'; '17pt'}; % The main experiment parameters min_outlier_fraction = 0.05;%0.05; max_outlier_fraction = 0.25; outlier_fraction_step = 0.025; p = 0.99; %% Run the benchmark %prepare the overall result arrays number_outlier_fraction_levels = round((max_outlier_fraction - min_outlier_fraction) / outlier_fraction_step + 1); num_algorithms = size(algorithms,1); expected_number_iterations = zeros(num_algorithms,number_outlier_fraction_levels); outlier_fraction_levels = zeros(1,number_outlier_fraction_levels); %Run the experiment for n=1:number_outlier_fraction_levels outlier_fraction = (n - 1) * outlier_fraction_step + min_outlier_fraction; outlier_fraction_levels(1,n) = outlier_fraction; display(['Analyzing outlier fraction level: ' num2str(outlier_fraction)]) %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms expected_number_iterations(a,n) = log(1-p)/log(1-(1-outlier_fraction)^(algorithms(a,1))); end end %% Plot the results figure(1) plot(outlier_fraction_levels,expected_number_iterations,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('outlier fraction') ylabel('expected number iterations') grid onopengv/matlab/make_mex.sh0000775016516101651610000000176013635643413014403 0ustar dimadima#!/bin/bash # Generate MEX files by compiling from Matlab # This scripts intends to automate the compilation process # by following the instructions provided in # http://laurentkneip.github.io/opengv/page_installation.html#sec_installation_5 # We assume the installation configuration is standard # so that every dependency can be found in an automated way # We assume a launcher command is available: matlab # Add OpenGV library directory to the path export LD_LIBRARY_PATH=../build/lib:$LD_LIBRARY_PATH # Find path to Eigen library (assumes CMake has cached EIGEN_INCLUDE_DIRS) # See https://stackoverflow.com/questions/8474753/how-to-get-a-cmake-variable-from-the-command-line EigenPath=$(cmake -L ../build | grep EIGEN_INCLUDE_DIRS | cut -d "=" -f2) # Call Matlab with the compilation command matlab -nodisplay -nosplash -nodesktop \ -r "mex -I../include -I${EigenPath} -L../build/lib -lopengv opengv.cpp -cxx, mex -I../include -I${EigenPath} -L../build/lib -lopengv opengv_donotuse.cpp -cxx, exit" opengv/matlab/opengv_experimental2.cpp0000664016516101651610000001161213344612246017111 0ustar dimadimastatic const char *copyright = " Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved."; /****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ // Matlab usage: // // X = opengv_experimental2( data1, data2, algorithm ) // // where // data1, data2 are matched points of dimension 6xn // algorithm is 0 for sixpt, 1 for ge, and 2 for seventeenpt // X is a 3x5 matrix returning the found transformation, plus the number of // Ransac-iterations and inliers // //matlab header //standard headers #include #include #include #include "mex.h" //include generic headers for opengv stuff #include //include the matlab-adapters #include //expose all ransac-facilities to matlab #include #include typedef opengv::sac_problems::relative_pose::NoncentralRelativePoseSacProblem nrelRansac; typedef std::shared_ptr nrelRansacPtr; // The main mex-function void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] ) { // Characterize the type of the call const mxArray *data1 = prhs[0]; const mxArray *data2 = prhs[1]; const mxArray *temp1 = prhs[2]; double *temp2 = (double*) mxGetData(temp1); int algorithm = floor(temp2[0]+0.01); const mwSize *data1dim = mxGetDimensions(data1); const mwSize *data2dim = mxGetDimensions(data2); //create three pointers to absolute, relative, and point_cloud adapters here opengv::relative_pose::RelativeAdapterBase* relativeAdapter = new opengv::relative_pose::MANoncentralRelative( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); nrelRansacPtr problem; switch(algorithm) { case 0: problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SIXPT ) ); break; case 1: problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::GE ) ); break; case 2: problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SEVENTEENPT ) ); break; } opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 10000000; ransac.computeModel(); Eigen::Matrix result; result.block<3,4>(0,0) = ransac.model_coefficients_; result(0,4) = ransac.iterations_; result(1,4) = ransac.inliers_.size(); int dims[2]; dims[0] = 3; dims[1] = 5; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), result.data(), 15*sizeof(double)); } opengv/matlab/benchmark_relative_pose.m0000664016516101651610000000762213344612246017307 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 1; % Getting 10 points, and testing all algorithms with the respective number of points pt_number = 10; % noise test, so no outliers outlier_fraction = 0.0; % repeat 5000 tests per noise level iterations = 5000; % The algorithms we want to test algorithms = { 'fivept_stewenius'; 'fivept_nister'; 'fivept_kneip'; 'sevenpt'; 'eightpt'; 'eigensolver'; 'rel_nonlin_central' }; % Some parameter that tells us what the result means returns = [ 1, 1, 0, 1, 1, 0, 2 ]; % 1means essential matrix(ces) needing decomposition, %0 means rotation matrix(ces), %2 means transformation matrix % This defines the number of points used for every algorithm indices = { [1, 2, 3, 4, 5]; [1, 2, 3, 4, 5]; [1, 2, 3, 4, 5]; [1, 2, 3, 4, 5, 6, 7]; [1, 2, 3, 4, 5, 6, 7, 8]; [1, 2, 3, 4, 5, 6, 7, 8, 9, 10]; [1, 2, 3, 4, 5, 6, 7, 8, 9, 10] }; % The name of the algorithms in the final plots names = { '5pt (Stewenius)'; '5pt (Nister)'; '5pt (Kneip)'; '7pt'; '8pt'; 'eigensolver (10pts)'; 'nonlin. opt. (10pts)' }; % The maximum noise to analyze max_noise = 5.0; % The step in between different noise levels noise_step = 0.1; %% Run the benchmark %prepare the overall result arrays number_noise_levels = max_noise / noise_step + 1; num_algorithms = size(algorithms,1); mean_rotation_errors = zeros(num_algorithms,number_noise_levels); median_rotation_errors = zeros(num_algorithms,number_noise_levels); noise_levels = zeros(1,number_noise_levels); %Run the experiment for n=1:number_noise_levels noise = (n - 1) * noise_step; noise_levels(1,n) = noise; display(['Analyzing noise level: ' num2str(noise)]) rotation_errors = zeros(num_algorithms,iterations); counter = 0; validIterations = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; R_gt = R; % run all algorithms allValid = 1; for a=1:num_algorithms Out = opengv(algorithms{a},indices{a},v1,v2,T_perturbed); if ~isempty(Out) if returns(1,a) == 1 temp = transformEssentials(Out); Out = temp; end if returns(1,a) == 2 temp = Out(:,1:3); Out = temp; end rotation_errors(a,validIterations+1) = evaluateRotationError( R_gt, Out ); else allValid = 0; break; end end if allValid == 1 validIterations = validIterations +1; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms mean_rotation_errors(a,n) = mean(rotation_errors(a,1:validIterations)); median_rotation_errors(a,n) = median(rotation_errors(a,1:validIterations)); end end %% Plot the results figure(1) plot(noise_levels,mean_rotation_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean rot. error [rad]') grid on figure(2) plot(noise_levels,median_rotation_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median rot. error [rad]') grid on opengv/matlab/benchmark_absolute_pose.m0000664016516101651610000000722213344612246017306 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 1; % let's only get 6 points, and generate new ones in each iteration pt_number = 6; % noise test, so no outliers outlier_fraction = 0.0; % repeat 5000 iterations per noise level iterations = 5000; % The algorithms we want to test algorithms = { 'p3p_kneip'; 'p3p_gao'; 'epnp'; 'abs_nonlin_central'; 'upnp'; 'upnp' }; % This defines the number of points used for every algorithm indices = { [1, 2, 3]; [1, 2, 3]; [1, 2, 3, 4, 5, 6]; [1, 2, 3, 4, 5, 6]; [1, 2, 3, 4, 5, 6]; [1, 2, 3] }; % The name of the algorithms on the plots names = { 'P3P (Kneip)'; 'P3P (Gao)'; 'EPnP'; 'nonlinear optimization'; 'UPnP'; 'UPnP (minimal)' }; % The maximum noise to analyze max_noise = 5.0; % The step in between different noise levels noise_step = 0.1; %% Run the benchmark %prepare the overall result arrays number_noise_levels = max_noise / noise_step + 1; num_algorithms = size(algorithms,1); mean_position_errors = zeros(num_algorithms,number_noise_levels); mean_rotation_errors = zeros(num_algorithms,number_noise_levels); median_position_errors = zeros(num_algorithms,number_noise_levels); median_rotation_errors = zeros(num_algorithms,number_noise_levels); noise_levels = zeros(1,number_noise_levels); %Run the experiment for n=1:number_noise_levels noise = (n - 1) * noise_step; noise_levels(1,n) = noise; display(['Analyzing noise level: ' num2str(noise)]) position_errors = zeros(num_algorithms,iterations); rotation_errors = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [points,v,t,R] = create2D3DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; T_gt = [R,t]; % run all algorithms for a=1:num_algorithms T = opengv(algorithms{a},indices{a},points,v,T_perturbed); [position_error, rotation_error] = evaluateTransformationError( T_gt, T ); position_errors(a,i) = position_error; rotation_errors(a,i) = rotation_error; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms mean_position_errors(a,n) = mean(position_errors(a,:)); median_position_errors(a,n) = median(position_errors(a,:)); mean_rotation_errors(a,n) = mean(rotation_errors(a,:)); median_rotation_errors(a,n) = median(rotation_errors(a,:)); end end %% Plot the results figure(1) plot(noise_levels',mean_rotation_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean rot. error [rad]') grid on figure(2) plot(noise_levels',median_rotation_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median rot. error [rad]') grid on figure(3) plot(noise_levels',mean_position_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean pos. error [m]') grid on figure(4) plot(noise_levels',median_position_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median pos. error [m]') grid onopengv/matlab/plot_arun_error.m0000664016516101651610000000302713344612246015643 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % noncentral case cam_number = 4; % Getting 17 points, and testing all algorithms with the respective number of points pt_number = 8; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 tests per noise level iterations = 10000; % The algorithms we want to test algorithms = { 'ge2' }; % This defines the number of points used for every algorithm indices = { [1:1:8] }; % The name of the algorithms in the final plots names = { 'arun (8pt)' }; % The maximum noise to analyze noise = 0.5; %% Run the benchmark %Run the experiment rotation_errors = zeros(1,iterations); counter = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DOmniExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; T_init = [eye(3),zeros(3,1)]; T_gt = [R,t]; Out = opengv(algorithms{1},indices{1},v1,v2,T_perturbed); rotation_error = evaluateRotationError( R, Out(1:3,1:3) ); rotation_errors(1,i) = rotation_error; counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %% Plot the results hist(rad2deg(rotation_errors)) xlabel('rotation error [deg]') ylabel('occurence') grid onopengv/matlab/ransac_experiment3.m0000664016516101651610000000410313344612246016215 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % The name of the algorithms in the final plots names = { '6pt'; 'ge (8pt)'; '17pt'}; % The main experiment parameters min_outlier_fraction = 0.05; max_outlier_fraction = 0.45; outlier_fraction_step = 0.05; %% Run the benchmark %prepare the overall result arrays number_outlier_fraction_levels = round((max_outlier_fraction - min_outlier_fraction) / outlier_fraction_step + 1); num_algorithms = size(names,1); mean_number_iterations = zeros(num_algorithms,number_outlier_fraction_levels); mean_execution_times = zeros(num_algorithms,number_outlier_fraction_levels); outlier_fraction_levels = zeros(1,number_outlier_fraction_levels); %Run the experiment for n=1:number_outlier_fraction_levels outlier_fraction = (n - 1) * outlier_fraction_step + min_outlier_fraction; outlier_fraction_levels(1,n) = outlier_fraction; display(['Analyzing outlier fraction level: ' num2str(outlier_fraction)]) clear number_iterations clear execution_times temp_file_name1 = ['number_iterations_' num2str(outlier_fraction) '.mat']; temp_file_name2 = ['execution_times_' num2str(outlier_fraction) '.mat']; load(temp_file_name1) load(temp_file_name2) %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms mean_number_iterations(a,n) = mean(number_iterations(a,:)); mean_execution_times(a,n) = mean(execution_times(a,:)); end end %% Plot the results figure(1) plot(outlier_fraction_levels,mean_number_iterations,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('outlier fraction') ylabel('mean number iterations') axis([0.05 0.25 0 1500]) grid on figure(2) hold on plot(outlier_fraction_levels(1,1:6),mean_execution_times(1,1:6),'LineWidth',2) plot(outlier_fraction_levels,mean_execution_times(2:3,:),'LineWidth',2) legend(names,'Location','NorthWest') xlabel('outlier fraction') ylabel('mean execution time [s]') axis([0.05 0.45 0 40]) grid onopengv/matlab/benchmark_absolute_pose_execution_times.m0000664016516101651610000000326013344612246022570 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 1; % let's only get 6 points, and generate new ones in each iteration pt_number = 50; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 iterations iterations = 1000; % The algorithms we want to test algorithms = { 'p2p'; 'p3p_kneip'; 'p3p_gao'; 'epnp'; 'upnp' }; % This defines the number of points used for every algorithm indices = { [1, 2]; [1, 2, 3]; [1, 2, 3]; [1:1:50]; [1:1:50] }; % The name of the algorithms on the plots names = { 'P2P'; 'P3P (Kneip)'; 'P3P (Gao)'; 'EPnP (50pts)'; 'UPnP (50pts)'}; % The noise in this experiment noise = 1.0; %% Run the benchmark %prepare the overall result array num_algorithms = size(algorithms,1); execution_times = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [points,v,t,R] = create2D3DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; % run all algorithms for a=1:num_algorithms tic; T = opengv_donotuse(algorithms{a},indices{a},points,v,T_perturbed); execution_times(a,i) = toc/20.0; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations)]); end end %% Plot the results bins = [0.000001:0.000001:0.00001]; hist(execution_times',bins) legend(names,'Location','NorthWest') xlabel('execution times [s]') grid on mean(execution_times') opengv/matlab/helpers/0000775016516101651610000000000013344612246013711 5ustar dimadimaopengv/matlab/helpers/createMulti2D2DOmniExperiment.m0000664016516101651610000000721613344612246021613 0ustar dimadimafunction [v1, v2, cam_offsets, t, R ] = createMulti2D2DOmniExperiment( pt_per_cam, cam_number, noise, outlier_fraction ) %% generate the camera system cam_distance = 1.0; %% set a regular camera system with 2 or 4 cameras here if cam_number == 2 cam_offsets = [ cam_distance -cam_distance; 0.0 0.0; 0.0 0.0 ]; else cam_number = 4; % only two or 4 supported for this experiment cam_offsets = [ cam_distance 0.0 -cam_distance 0.0; 0.0 cam_distance 0.0 -cam_distance; 0.0 0.0 0.0 0.0 ]; end %% generate random view-points max_parallax = 2.0; max_rotation = 0.5; position1 = zeros(3,1); rotation1 = eye(3); position2 = max_parallax * 2.0 * (rand(3,1) - repmat(0.5,3,1)); rotation2 = generateBoundedR(max_rotation); %% Generate random point-cloud avg_depth_over_cam_distance = 10.0; maxDepth = 5.0; p = cell([cam_number 1]); for cam=1:cam_number normalizedPoints = 2.0*(rand(3,pt_per_cam)-repmat(0.5,3,pt_per_cam)); p{cam,1} = maxDepth * normalizedPoints; end %% Now create the correspondences by looping through the cameras focal_length = 800.0; v1 = cell([cam_number 1]); v2 = cell([cam_number 1]); for cam=1:cam_number v1{cam,1} = zeros(3,pt_per_cam); v2{cam,1} = zeros(3,pt_per_cam); for i=1:pt_per_cam cam_offset = cam_offsets(:,cam); %special: shift the point in the first frame along current camera axis, which guarantees homogeneous distribution temp = p{cam,1}(:,i) + avg_depth_over_cam_distance * cam_offset; p{cam,1}(:,i) = temp; body_point1 = rotation1' * (p{cam,1}(:,i)-position1); body_point2 = rotation2' * (p{cam,1}(:,i)-position2); % we actually omit the can rotation here by unrotating the bearing % vectors already bearingVector1 = body_point1 - cam_offset; bearingVector2 = body_point2 - cam_offset; bearingVector1_norm = norm(bearingVector1); bearingVector2_norm = norm(bearingVector2); bearingVector1 = bearingVector1/bearingVector1_norm; bearingVector2 = bearingVector2/bearingVector2_norm; % add noise to the bearing vectors here bearingVector1_noisy = addNoise(bearingVector1,focal_length,noise); bearingVector2_noisy = addNoise(bearingVector2,focal_length,noise); % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector1_norm = norm(bearingVector1_noisy); bearingVector2_norm = norm(bearingVector2_noisy); v1{cam,1}(:,i) = [bearingVector1_noisy./bearingVector1_norm]; v2{cam,1}(:,i) = [bearingVector2_noisy./bearingVector2_norm]; end end %% Add outliers outliers_per_cam = floor(outlier_fraction*pt_per_cam); if outliers_per_cam > 0 for cam=1:cam_number for i=1:outliers_per_cam cam_offset = cam_offsets(:,cam); %generate random point normalizedPoint = 2.0*(rand(3,1)-repmat(0.5,3,1)); point = maxDepth * normalizedPoint + avg_depth_over_cam_distance * cam_offset; body_point2 = rotation2' * (point-position2); % store the point (no need to add noise) bearingVector2 = body_point2 - cam_offset; % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector2_norm = norm(bearingVector2); v2{cam,1}(:,i) = [bearingVector2./bearingVector2_norm]; end end end %% compute relative translation and rotation R = rotation1' * rotation2; t = rotation1' * (position2 - position1);opengv/matlab/helpers/generateRandomR.m0000664016516101651610000000105513344612246017145 0ustar dimadimafunction R = generateRandomR() rpy = pi()*2.0*(rand(3,1)-repmat(0.5,3,1)); rpy(2,1) = 0.5*rpy(2,1); R1 = zeros(3,3); R1(1,1) = 1.0; R1(2,2) = cos(rpy(1,1)); R1(2,3) = -sin(rpy(1,1)); R1(3,2) = -R1(2,3); R1(3,3) = R1(2,2); R2 = zeros(3,3); R2(1,1) = cos(rpy(2,1)); R2(1,3) = sin(rpy(2,1)); R2(2,2) = 1.0; R2(3,1) = -R2(1,3); R2(3,3) = R2(1,1); R3 = zeros(3,3); R3(1,1) = cos(rpy(3,1)); R3(1,2) = -sin(rpy(3,1)); R3(2,1) =-R3(1,2); R3(2,2) = R3(1,1); R3(3,3) = 1.0; R = R3 * R2 * R1; endopengv/matlab/helpers/createMulti2D2DExperiment.m0000664016516101651610000000711613344612246020767 0ustar dimadimafunction [v1, v2, cam_offsets, t, R ] = createMulti2D2DExperiment( pt_per_cam, cam_number, noise, outlier_fraction ) %% generate the camera system avg_cam_distance = 0.5; cam_offsets = zeros(3,cam_number); %cam_rotations = zeros(3,cam_number*3); if cam_number == 1 cam_offsets = zeros(3,1); %cam_rotations = eye(3); else for i=1:cam_number cam_offsets(:,i) = avg_cam_distance * generateRandomR() * [1.0; 0.0; 0.0]; %cam_rotations(:,(i-1)*3+1:(i-1)*3+3) = generateRandomR(); end end %% generate random view-points max_parallax = 2.0; max_rotation = 0.5; position1 = zeros(3,1); rotation1 = eye(3); position2 = max_parallax * 2.0 * (rand(3,1) - repmat(0.5,3,1)); rotation2 = generateBoundedR(max_rotation); %% Generate random point-clouds minDepth = 4.0; maxDepth = 8.0; p = cell([cam_number 1]); for cam=1:cam_number normalizedPoints = 2.0*(rand(3,pt_per_cam)-repmat(0.5,3,pt_per_cam)); norms = sqrt(sum(normalizedPoints.*normalizedPoints)); directions = normalizedPoints./repmat(norms,3,1); p{cam,1} = (maxDepth-minDepth) * normalizedPoints + minDepth * directions; end %% Now create the correspondences by looping through the cameras focal_length = 800.0; v1 = cell([cam_number 1]); v2 = cell([cam_number 1]); for cam=1:cam_number v1{cam,1} = zeros(3,pt_per_cam); v2{cam,1} = zeros(3,pt_per_cam); for i=1:pt_per_cam cam_offset = cam_offsets(:,cam); %cam_rotation = cam_rotations(:,(cam-1)*3+1:(cam-1)*3+3); body_point1 = rotation1' * (p{cam,1}(:,i)-position1); body_point2 = rotation2' * (p{cam,1}(:,i)-position2); % we actually omit the cam rotation here by unrotating the bearing % vectors already bearingVector1 = body_point1 - cam_offset; bearingVector2 = body_point2 - cam_offset; bearingVector1_norm = norm(bearingVector1); bearingVector2_norm = norm(bearingVector2); bearingVector1 = bearingVector1/bearingVector1_norm; bearingVector2 = bearingVector2/bearingVector2_norm; % add noise to the bearing vectors here bearingVector1_noisy = addNoise(bearingVector1,focal_length,noise); bearingVector2_noisy = addNoise(bearingVector2,focal_length,noise); % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you should not change this in this experiment!) bearingVector1_norm = norm(bearingVector1_noisy); bearingVector2_norm = norm(bearingVector2_noisy); v1{cam,1}(:,i) = bearingVector1_noisy./bearingVector1_norm; v2{cam,1}(:,i) = bearingVector2_noisy./bearingVector2_norm; end end %% Add outliers outliers_per_cam = floor(outlier_fraction*pt_per_cam); if outliers_per_cam > 0 for cam=1:cam_number for i=1:outliers_per_cam cam_offset = cam_offsets(:,cam); %cam_rotation = cam_rotations(:,(cam-1)*3+1:(cam-1)*3+3); %generate random point normalizedPoint = 2.0*(rand(3,1)-repmat(0.5,3,1)); norm1 = sqrt(sum(normalizedPoint.*normalizedPoint)); direction = normalizedPoint./norm1; point = (maxDepth-minDepth) * normalizedPoint + minDepth * direction; body_point2 = rotation2' * (point-position2); % store the point (no need to add noise) bearingVector2 = body_point2 - cam_offset; bearingVector2_norm = norm(bearingVector2); v2{cam,1}(:,i) = bearingVector2./bearingVector2_norm; end end end %% compute relative translation and rotation R = rotation1' * rotation2; t = rotation1' * (position2 - position1);opengv/matlab/helpers/cayley2rot.m0000664016516101651610000000106513344612246016166 0ustar dimadimafunction R = cayley2rot(v) cayley0 = v(1,1); cayley1 = v(2,1); cayley2 = v(3,1); R = zeros(3,3); scale = 1+cayley0^2+cayley1^2+cayley2^2; R(1,1) = 1+cayley0^2-cayley1^2-cayley2^2; R(1,2) = 2*(cayley0*cayley1-cayley2); R(1,3) = 2*(cayley0*cayley2+cayley1); R(2,1) = 2*(cayley0*cayley1+cayley2); R(2,2) = 1-cayley0^2+cayley1^2-cayley2^2; R(2,3) = 2*(cayley1*cayley2-cayley0); R(3,1) = 2*(cayley0*cayley2-cayley1); R(3,2) = 2*(cayley1*cayley2+cayley0); R(3,3) = 1-cayley0^2-cayley1^2+cayley2^2; R = (1/scale) * R;opengv/matlab/helpers/generateBoundedR.m0000664016516101651610000000103213344612246017300 0ustar dimadimafunction R = generateBoundedR( bound ) rpy = bound*2.0*(rand(3,1)-repmat(0.5,3,1)); R1 = zeros(3,3); R1(1,1) = 1.0; R1(2,2) = cos(rpy(1,1)); R1(2,3) = -sin(rpy(1,1)); R1(3,2) = -R1(2,3); R1(3,3) = R1(2,2); R2 = zeros(3,3); R2(1,1) = cos(rpy(2,1)); R2(1,3) = sin(rpy(2,1)); R2(2,2) = 1.0; R2(3,1) = -R2(1,3); R2(3,3) = R2(1,1); R3 = zeros(3,3); R3(1,1) = cos(rpy(3,1)); R3(1,2) = -sin(rpy(3,1)); R3(2,1) =-R3(1,2); R3(2,2) = R3(1,1); R3(3,3) = 1.0; R = R3 * R2 * R1; endopengv/matlab/helpers/transformEssentials.m0000664016516101651610000000272313344612246020141 0ustar dimadimafunction Rs = transformEssentials(Es) temp = size(size(Es)); numberSolutions = 1; if temp(1,2) == 3 temp2 = size(Es); numberSolutions = temp2(1,3); end if numberSolutions == 1 Rs = zeros(3,3,2); [U,~,V] = svd(Es); W = [0 -1 0; 1 0 0; 0 0 1]; Rs(1:3,1:3) = U * W * V'; Rs(1:3,4:6) = U * W' * V'; if( det(Rs(1:3,1:3)) < 0 ) Rs(1:3,1:3) = -Rs(1:3,1:3); end if( det(Rs(1:3,4:6)) < 0 ) Rs(1:3,4:6) = -Rs(1:3,4:6); end else Rs_temp = zeros(3,3,2*numberSolutions); index = 0; for i=1:numberSolutions %Check if there is any Nan if ~isnan(Es(1,1,i)) [U,~,V] = svd(Es(:,:,i)); W = [0 -1 0; 1 0 0; 0 0 1]; index = index + 1; Rs_temp( :,:, index ) = U * W * V'; if(det(Rs_temp( :,:, index )) < 0) Rs_temp( :,:, index ) = -Rs_temp( :,:, index ); end index = index + 1; Rs_temp( :,:, index ) = U * W' * V'; if(det(Rs_temp( :,:, index )) < 0) Rs_temp( :,:, index ) = -Rs_temp( :,:, index ); end end end Rs = Rs_temp(:,:,1:index); end end opengv/matlab/helpers/rodrigues.m0000664016516101651610000001067713344612246016105 0ustar dimadimafunction [out,dout]=rodrigues(in) % RODRIGUES Transform rotation matrix into rotation vector and viceversa. % % Sintax: [OUT]=RODRIGUES(IN) % If IN is a 3x3 rotation matrix then OUT is the % corresponding 3x1 rotation vector % if IN is a rotation 3-vector then OUT is the % corresponding 3x3 rotation matrix % %% %% Copyright (c) March 1993 -- Pietro Perona %% California Institute of Technology %% %% ALL CHECKED BY JEAN-YVES BOUGUET, October 1995. %% FOR ALL JACOBIAN MATRICES !!! LOOK AT THE TEST AT THE END !! %% BUG when norm(om)=pi fixed -- April 6th, 1997; %% Jean-Yves Bouguet %% Add projection of the 3x3 matrix onto the set of special ortogonal matrices SO(3) by SVD -- February 7th, 2003; %% Jean-Yves Bouguet [m,n] = size(in); %bigeps = 10e+4*eps; bigeps = 10e+20*eps; if ((m==1) & (n==3)) | ((m==3) & (n==1)) %% it is a rotation vector theta = norm(in); if theta < eps R = eye(3); %if nargout > 1, dRdin = [0 0 0; 0 0 1; 0 -1 0; 0 0 -1; 0 0 0; 1 0 0; 0 1 0; -1 0 0; 0 0 0]; %end; else if n==length(in) in=in'; end; %% make it a column vec. if necess. %m3 = [in,theta] dm3din = [eye(3);in'/theta]; omega = in/theta; %m2 = [omega;theta] dm2dm3 = [eye(3)/theta -in/theta^2; zeros(1,3) 1]; alpha = cos(theta); beta = sin(theta); gamma = 1-cos(theta); omegav=[[0 -omega(3) omega(2)];[omega(3) 0 -omega(1)];[-omega(2) omega(1) 0 ]]; A = omega*omega'; %m1 = [alpha;beta;gamma;omegav;A]; dm1dm2 = zeros(21,4); dm1dm2(1,4) = -sin(theta); dm1dm2(2,4) = cos(theta); dm1dm2(3,4) = sin(theta); dm1dm2(4:12,1:3) = [0 0 0 0 0 1 0 -1 0; 0 0 -1 0 0 0 1 0 0; 0 1 0 -1 0 0 0 0 0]'; w1 = omega(1); w2 = omega(2); w3 = omega(3); dm1dm2(13:21,1) = [2*w1;w2;w3;w2;0;0;w3;0;0]; dm1dm2(13: 21,2) = [0;w1;0;w1;2*w2;w3;0;w3;0]; dm1dm2(13:21,3) = [0;0;w1;0;0;w2;w1;w2;2*w3]; R = eye(3)*alpha + omegav*beta + A*gamma; dRdm1 = zeros(9,21); dRdm1([1 5 9],1) = ones(3,1); dRdm1(:,2) = omegav(:); dRdm1(:,4:12) = beta*eye(9); dRdm1(:,3) = A(:); dRdm1(:,13:21) = gamma*eye(9); dRdin = dRdm1 * dm1dm2 * dm2dm3 * dm3din; end; out = R; dout = dRdin; %% it is prob. a rot matr. elseif ((m==n) & (m==3) & (norm(in' * in - eye(3)) < bigeps)... & (abs(det(in)-1) < bigeps)) R = in; % project the rotation matrix to SO(3); [U,S,V] = svd(R); R = U*V'; tr = (trace(R)-1)/2; dtrdR = [1 0 0 0 1 0 0 0 1]/2; theta = real(acos(tr)); if sin(theta) >= 1e-5, dthetadtr = -1/sqrt(1-tr^2); dthetadR = dthetadtr * dtrdR; % var1 = [vth;theta]; vth = 1/(2*sin(theta)); dvthdtheta = -vth*cos(theta)/sin(theta); dvar1dtheta = [dvthdtheta;1]; dvar1dR = dvar1dtheta * dthetadR; om1 = [R(3,2)-R(2,3), R(1,3)-R(3,1), R(2,1)-R(1,2)]'; dom1dR = [0 0 0 0 0 1 0 -1 0; 0 0 -1 0 0 0 1 0 0; 0 1 0 -1 0 0 0 0 0]; % var = [om1;vth;theta]; dvardR = [dom1dR;dvar1dR]; % var2 = [om;theta]; om = vth*om1; domdvar = [vth*eye(3) om1 zeros(3,1)]; dthetadvar = [0 0 0 0 1]; dvar2dvar = [domdvar;dthetadvar]; out = om*theta; domegadvar2 = [theta*eye(3) om]; dout = domegadvar2 * dvar2dvar * dvardR; else if tr > 0; % case norm(om)=0; out = [0 0 0]'; dout = [0 0 0 0 0 1/2 0 -1/2 0; 0 0 -1/2 0 0 0 1/2 0 0; 0 1/2 0 -1/2 0 0 0 0 0]; else % case norm(om)=pi; %% fixed April 6th out = theta * (sqrt((diag(R)+1)/2).*[1;2*(R(1,2:3)>=0)'-1]); %keyboard; if nargout > 1, fprintf(1,'WARNING!!!! Jacobian domdR undefined!!!\n'); dout = NaN*ones(3,9); end; end; end; else error('Neither a rotation matrix nor a rotation vector were provided'); end; return; %% test of the Jacobians: %%%% TEST OF dRdom: om = randn(3,1); dom = randn(3,1)/1000000; [R1,dR1] = rodrigues(om); R2 = rodrigues(om+dom); R2a = R1 + reshape(dR1 * dom,3,3); gain = norm(R2 - R1)/norm(R2 - R2a) %%% TEST OF dOmdR: om = randn(3,1); R = rodrigues(om); dom = randn(3,1)/10000; dR = rodrigues(om+dom) - R; [omc,domdR] = rodrigues(R); [om2] = rodrigues(R+dR); om_app = omc + domdR*dR(:); gain = norm(om2 - omc)/norm(om2 - om_app) %%% OTHER BUG: (FIXED NOW!!!) omu = randn(3,1); omu = omu/norm(omu) om = pi*omu; [R,dR]= rodrigues(om); [om2] = rodrigues(R); [om om2] %%% NORMAL OPERATION om = randn(3,1); [R,dR]= rodrigues(om); [om2] = rodrigues(R); [om om2]opengv/matlab/helpers/create2D3DExperiment.m0000664016516101651610000000674213344612246017761 0ustar dimadimafunction [points, v, t, R ] = create2D3DExperiment( pt_number, cam_number, noise, outlier_fraction ) %% generate the camera system avg_cam_distance = 0.5; cam_offsets = zeros(3,cam_number); %cam_rotations = zeros(3,cam_number*3); if cam_number == 1 cam_offsets = zeros(3,1); %cam_rotations = eye(3); else for i=1:cam_number cam_offsets(:,i) = avg_cam_distance * generateRandomR() * [1.0; 0.0; 0.0]; %cam_rotations(:,(i-1)*3+1:(i-1)*3+3) = generateRandomR(); end end %% generate random view-points max_parallax = 2.0; max_rotation = 0.5; position = max_parallax * 2.0 * (rand(3,1) - repmat(0.5,3,1)); rotation = generateBoundedR(max_rotation); %% Generate random point-cloud minDepth = 4.0; maxDepth = 8.0; normalizedPoints = 2.0*(rand(3,pt_number)-repmat(0.5,3,pt_number)); norms = sqrt(sum(normalizedPoints.*normalizedPoints)); directions = normalizedPoints./repmat(norms,3,1); points = (maxDepth-minDepth) * normalizedPoints + minDepth * directions; %% Now create the correspondences by looping through the cameras focal_length = 800.0; v = zeros(6,pt_number); cam_correspondence = 1; cam_correspondences = zeros(1,pt_number); for i=1:pt_number cam_offset = cam_offsets(:,cam_correspondence); %cam_rotation = cam_rotations(:,(cam_correspondence-1)*3+1:(cam_correspondence-1)*3+3); body_point = rotation' * (points(:,i)-position); % we actually omit the can rotation here by unrotating the bearing % vectors already bearingVector = body_point - cam_offset; bearingVector_norm = norm(bearingVector); bearingVector = bearingVector/bearingVector_norm; % add noise to the bearing vectors here bearingVector_noisy = addNoise(bearingVector,focal_length,noise); % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector_norm = norm(bearingVector_noisy); v(:,i) = [bearingVector_noisy./bearingVector_norm; cam_offset]; % change the camera correspondence cam_correspondences(1,i) = cam_correspondence; cam_correspondence = cam_correspondence + 1; if cam_correspondence > cam_number cam_correspondence = 1; end end %% Add outliers number_outliers = floor(outlier_fraction*pt_number); if number_outliers > 0 for i=1:number_outliers cam_correspondence = cam_correspondences(1,i); cam_offset = cam_offsets(:,cam_correspondence); %cam_rotation = cam_rotations(:,(cam_correspondence-1)*3+1:(cam_correspondence-1)*3+3); %generate random point normalizedPoint = 2.0*(rand(3,1)-repmat(0.5,3,1)); norm1 = sqrt(sum(normalizedPoint.*normalizedPoint)); direction = normalizedPoint./norm1; point = (maxDepth-minDepth) * normalizedPoint + minDepth * direction; body_point = rotation' * (point-position); % store the point (no need to add noise) bearingVector = body_point - cam_offset; % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector_norm = norm(bearingVector); v(:,i) = [bearingVector./bearingVector_norm; cam_offset]; end end %% copy over the position and orientation t = position; R = rotation; %% cut the cam offsets in the single camera (e.g. central case) if cam_number == 1 v = v(1:3,:); endopengv/matlab/helpers/evaluateTransformationError.m0000664016516101651610000000235713344612246021645 0ustar dimadimafunction [position_error,rotation_error] = evaluateTransformationError(T_gt,T) temp = size(size(T)); numberSolutions = 1; if temp(1,2) == 3 temp2 = size(T); numberSolutions = temp2(1,3); end if numberSolutions == 1 position_error = norm(T_gt(:,4)-T(:,4)); rotation_error = norm(rodrigues(T_gt(:,1:3)'*T(:,1:3))); else position_errors = zeros(1,numberSolutions); rotation_errors = zeros(1,numberSolutions); index = 0; for i=1:numberSolutions %Check if there is any Nan if ~isnan(T(1,1,i)) index = index + 1; position_errors(1,index) = norm(T_gt(:,4)-T(:,4,i)); rotation_errors(1,index) = norm(rodrigues(T_gt(:,1:3)'*T(:,1:3,i))); end end %find the smallest error (we are the most "nice" to algorithms returning multiple solutions, %and do the disambiguation by hand) [~,minIndex] = min(position_errors(1,1:index)); position_error = position_errors(1,minIndex); rotation_error = rotation_errors(1,minIndex); end endopengv/matlab/helpers/create2D2DExperiment.m0000664016516101651610000001003213344612246017743 0ustar dimadimafunction [v1, v2, t, R ] = create2D2DExperiment( pt_number, cam_number, noise, outlier_fraction ) %% generate the camera system avg_cam_distance = 0.5; cam_offsets = zeros(3,cam_number); %cam_rotations = zeros(3,cam_number*3); if cam_number == 1 cam_offsets = zeros(3,1); %cam_rotations = eye(3); else for i=1:cam_number cam_offsets(:,i) = avg_cam_distance * generateRandomR() * [1.0; 0.0; 0.0]; %cam_rotations(:,(i-1)*3+1:(i-1)*3+3) = generateRandomR(); end end %% generate random view-points max_parallax = 2.0; max_rotation = 0.5; position1 = zeros(3,1); rotation1 = eye(3); position2 = max_parallax * 2.0 * (rand(3,1) - repmat(0.5,3,1)); rotation2 = generateBoundedR(max_rotation); %% Generate random point-cloud minDepth = 4.0; maxDepth = 8.0; normalizedPoints = 2.0*(rand(3,pt_number)-repmat(0.5,3,pt_number)); norms = sqrt(sum(normalizedPoints.*normalizedPoints)); directions = normalizedPoints./repmat(norms,3,1); points = (maxDepth-minDepth) * normalizedPoints + minDepth * directions; %% Now create the correspondences by looping through the cameras focal_length = 800.0; v1 = zeros(6,pt_number); v2 = zeros(6,pt_number); cam_correspondence = 1; cam_correspondences = zeros(1,pt_number); for i=1:pt_number cam_offset = cam_offsets(:,cam_correspondence); %cam_rotation = cam_rotations(:,(cam_correspondence-1)*3+1:(cam_correspondence-1)*3+3); body_point1 = rotation1' * (points(:,i)-position1); body_point2 = rotation2' * (points(:,i)-position2); % we actually omit the can rotation here by unrotating the bearing % vectors already bearingVector1 = body_point1 - cam_offset; bearingVector2 = body_point2 - cam_offset; bearingVector1_norm = norm(bearingVector1); bearingVector2_norm = norm(bearingVector2); bearingVector1 = bearingVector1/bearingVector1_norm; bearingVector2 = bearingVector2/bearingVector2_norm; % add noise to the bearing vectors here bearingVector1_noisy = addNoise(bearingVector1,focal_length,noise); bearingVector2_noisy = addNoise(bearingVector2,focal_length,noise); % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector1_norm = norm(bearingVector1_noisy); bearingVector2_norm = norm(bearingVector2_noisy); v1(:,i) = [bearingVector1_noisy./bearingVector1_norm; cam_offset]; v2(:,i) = [bearingVector2_noisy./bearingVector2_norm; cam_offset]; % change the camera correspondence cam_correspondences(1,i) = cam_correspondence; cam_correspondence = cam_correspondence + 1; if cam_correspondence > cam_number cam_correspondence = 1; end end %% Add outliers number_outliers = floor(outlier_fraction*pt_number); if number_outliers > 0 for i=1:number_outliers cam_correspondence = cam_correspondences(1,i); cam_offset = cam_offsets(:,cam_correspondence); %cam_rotation = cam_rotations(:,(cam_correspondence-1)*3+1:(cam_correspondence-1)*3+3); %generate random point normalizedPoint = 2.0*(rand(3,1)-repmat(0.5,3,1)); norm1 = sqrt(sum(normalizedPoint.*normalizedPoint)); direction = normalizedPoint./norm1; point = (maxDepth-minDepth) * normalizedPoint + minDepth * direction; body_point2 = rotation2' * (point-position2); % store the point (no need to add noise) bearingVector2 = body_point2 - cam_offset; % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector2_norm = norm(bearingVector2); v2(:,i) = [bearingVector2./bearingVector2_norm; cam_offset]; end end %% compute relative translation and rotation R = rotation1' * rotation2; t = rotation1' * (position2 - position1); %% Cut the cam offset in the single camera case (e.g. central) if cam_number == 1 v1 = v1(1:3,:); v2 = v2(1:3,:); endopengv/matlab/helpers/evaluateRotationError.m0000664016516101651610000000220613344612246020427 0ustar dimadimafunction rotation_error = evaluateRotationError(R_gt,R) temp = size(size(R)); numberSolutions = 1; if temp(1,2) == 3 temp2 = size(R); numberSolutions = temp2(1,3); end if numberSolutions == 1 %rotation_error = norm(rodrigues(R_gt'*R)); rotation_error = norm( rodrigues(R_gt) - rodrigues(R) ); else rotation_errors = zeros(1,numberSolutions); index = 0; for i=1:numberSolutions %Check if there is any Nan if ~isnan(R(1,1,i)) index = index + 1; %rotation_errors(1,index) = norm(rodrigues(R_gt'*R(:,:,i))); rotation_errors(1,index) = norm( rodrigues(R_gt) - rodrigues(R(:,:,i)) ); end end %find the smallest error (we are the most "nice" to algorithms returning multiple solutions, %and do the disambiguation by hand) [~,minIndex] = min(rotation_errors(1,1:index)); rotation_error = rotation_errors(1,minIndex); end end opengv/matlab/helpers/perturb.m0000664016516101651610000000046313344612246015555 0ustar dimadimafunction [t_perturbed,R_perturbed] = perturb(t,R,amplitude) t_perturbed = t; r = rodrigues(R); for i=1:3 t_perturbed(i,1) = t_perturbed(i,1) + (rand-0.5)*2.0*amplitude; r(i,1) = r(i,1) + (rand-0.5)*2.0*amplitude; end R_perturbed = rodrigues(r); endopengv/matlab/helpers/addNoise.m0000664016516101651610000000246213344612246015621 0ustar dimadimafunction v_noisy = addNoise(v_clean,focal_length,pixel_noise) %find good vector in normal plane based on good conditioning inPlaneVector1 = zeros(3,1); if v_clean(1,1) > v_clean(2,1) && v_clean(1,1) > v_clean(3,1) inPlaneVector1(2,1) = 1.0; inPlaneVector1(3,1) = 0.0; inPlaneVector1(1,1) = 1.0/v_clean(1,1) * (-v_clean(2,1)); else if v_clean(2,1) > v_clean(3,1) && v_clean(2,1) > v_clean(1,1) inPlaneVector1(3,1) = 1.0; inPlaneVector1(1,1) = 0.0; inPlaneVector1(2,1) = 1.0/v_clean(2,1) * (-v_clean(3,1)); else %v_clean(3,1) > v_clean(1,1) && v_clean(3,1) > v_clean(2,1) inPlaneVector1(1,1) = 1.0; inPlaneVector1(2,1) = 0.0; inPlaneVector1(3,1) = 1.0/v_clean(3,1) * (-v_clean(1,1)); end end %normalize the in-plane vector inPlaneVector1 = inPlaneVector1 / norm(inPlaneVector1); inPlaneVector2 = cross(v_clean,inPlaneVector1); noiseX = pixel_noise * (rand-0.5)*2.0;% / sqrt(2); noiseY = pixel_noise * (rand-0.5)*2.0;% / sqrt(2); v_noisy = focal_length * v_clean + noiseX * inPlaneVector1 + noiseY * inPlaneVector2; v_noisy_norm = norm(v_noisy); v_noisy = v_noisy ./ v_noisy_norm; endopengv/matlab/helpers/create2D2DOmniExperiment.m0000664016516101651610000000760313344612246020600 0ustar dimadimafunction [v1, v2, t, R ] = create2D2DOmniExperiment( pt_number, cam_number, noise, outlier_fraction ) %% generate the camera system cam_distance = 1.0; %% set a regular camera system with 2 or 4 cameras here if cam_number == 2 cam_offsets = [ cam_distance -cam_distance; 0.0 0.0; 0.0 0.0 ]; else cam_number = 4; % only two or 4 supported for this experiment cam_offsets = [ cam_distance 0.0 -cam_distance 0.0; 0.0 cam_distance 0.0 -cam_distance; 0.0 0.0 0.0 0.0 ]; end %% generate random view-points max_parallax = 2.0; max_rotation = 0.5; position1 = zeros(3,1); rotation1 = eye(3); position2 = max_parallax * 2.0 * (rand(3,1) - repmat(0.5,3,1)); rotation2 = generateBoundedR(max_rotation); %% Generate random point-cloud avg_depth_over_cam_distance = 10.0; maxDepth = 5.0; normalizedPoints = 2.0*(rand(3,pt_number)-repmat(0.5,3,pt_number)); points = maxDepth * normalizedPoints; %% Now create the correspondences by looping through the cameras focal_length = 800.0; v1 = zeros(6,pt_number); v2 = zeros(6,pt_number); cam_correspondence = 1; cam_correspondences = zeros(1,pt_number); for i=1:pt_number cam_offset = cam_offsets(:,cam_correspondence); %cam_rotation = cam_rotations(:,(cam_correspondence-1)*3+1:(cam_correspondence-1)*3+3); %special: shift the point in the first frame along current camera axis, which guarantees homogeneous distribution temp = points(:,i) + avg_depth_over_cam_distance * cam_offset; points(:,i) = temp; body_point1 = rotation1' * (points(:,i)-position1); body_point2 = rotation2' * (points(:,i)-position2); % we actually omit the can rotation here by unrotating the bearing % vectors already bearingVector1 = body_point1 - cam_offset; bearingVector2 = body_point2 - cam_offset; bearingVector1_norm = norm(bearingVector1); bearingVector2_norm = norm(bearingVector2); bearingVector1 = bearingVector1/bearingVector1_norm; bearingVector2 = bearingVector2/bearingVector2_norm; % add noise to the bearing vectors here bearingVector1_noisy = addNoise(bearingVector1,focal_length,noise); bearingVector2_noisy = addNoise(bearingVector2,focal_length,noise); % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector1_norm = norm(bearingVector1_noisy); bearingVector2_norm = norm(bearingVector2_noisy); v1(:,i) = [bearingVector1_noisy./bearingVector1_norm; cam_offset]; v2(:,i) = [bearingVector2_noisy./bearingVector2_norm; cam_offset]; % change the camera correspondence cam_correspondences(1,i) = cam_correspondence; cam_correspondence = cam_correspondence + 1; if cam_correspondence > cam_number cam_correspondence = 1; end end %% Add outliers number_outliers = floor(outlier_fraction*pt_number); if number_outliers > 0 for i=1:number_outliers cam_correspondence = cam_correspondences(1,i); cam_offset = cam_offsets(:,cam_correspondence); %cam_rotation = cam_rotations(:,(cam_correspondence-1)*3+1:(cam_correspondence-1)*3+3); %generate random point normalizedPoint = 2.0*(rand(3,1)-repmat(0.5,3,1)); point = maxDepth * normalizedPoint + avg_depth_over_cam_distance * cam_offset; body_point2 = rotation2' * (point-position2); % store the point (no need to add noise) bearingVector2 = body_point2 - cam_offset; % store the normalized bearing vectors along with the cameras they are % being seen (we create correspondences that always originate from the % same camera, you can change this if you want) bearingVector2_norm = norm(bearingVector2); v2(:,i) = [bearingVector2./bearingVector2_norm; cam_offset]; end end %% compute relative translation and rotation R = rotation1' * rotation2; t = rotation1' * (position2 - position1);opengv/matlab/helpers/rot2cayley.m0000664016516101651610000000026013344612246016162 0ustar dimadimafunction v = rot2cayley(R) C1 = R-eye(3); C2 = R+eye(3); C = C1 * inv(C2); v = zeros(3,1); v(1,1) = -C(2,3); v(2,1) = C(1,3); v(3,1) = -C(1,2); endopengv/matlab/opengv_donotuse.cpp0000664016516101651610000016330713635643413016206 0ustar dimadimastatic const char *copyright = " Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved."; /****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ // Matlab usage: // // X = opengv ( method, data1, data2 ) // X = opengv ( method, indices, data1, data2 ) // X = opengv ( method, indices, data1, data2, prior ) // // where // method is a string that characterizes the algorithm to use // data1, data2 are matched points (each one of dimension 3xn or 6xn) // indices is a vector of indices indicating a subset of the correspondences // X is a 3xnxm matrix, where n is the second dimensionality of the solution space, // and m is the number of solutions // prior is a prior pose in case it is known (a matrix of format [R t]) // // Note that the indices of inliers can also be returned for Ransac methods // if adding a second left-hand side parameter upon function call // (format: [X, inliers] = opengv(...) ) //matlab header //standard headers #include #include #include #include "mex.h" //include generic headers for opengv stuff #include //include the matlab-adapters #include #include #include #include #include //expose all methods to matlab #include #include #include //expose all ransac-facilities to matlab #include #include #include #include #include #include #include // The different methods that can be used within Matlab static const char* methods[]= { // absolute_pose methods "p2p", // 3 "p3p_kneip", // 9 "p3p_gao", // 7 "epnp", // 4 "p3p_kneip_ransac", // 16 "p3p_gao_ransac", // 14 "epnp_ransac", // 11 "abs_nonlin_central", // 18 "gp3p", // 4 "gp3p_ransac", // 11 "gpnp", // 4 "abs_nonlin_noncentral", // 21 "upnp", // 4 // relative_pose methods "twopt", // 5 "twopt_rotationOnly", // 18 "rotationOnly", // 12 "fivept_stewenius", // 16 "fivept_nister", // 13 "fivept_kneip", // 12 "sevenpt", // 7 "eightpt", // 7 "eigensolver", // 11 "rotationOnly_ransac", // 19 "fivept_stewenius_ransac", // 23 "fivept_nister_ransac", // 20 "sevenpt_ransac", // 14 "eightpt_ransac", // 14 "eigensolver_ransac", // 18 "rel_nonlin_central", // 18 "sixpt", // 5 "seventeenpt", // 11 "ge", // 2 "sixpt_ransac", // 12 "seventeenpt_ransac", // 18 "ge_ransac", // 9 "rel_nonlin_noncentral", // 21 // point_cloud methods "threept_arun", // 12 "threept_arun_ransac" // 19 }; // The length of the method strings (needed for comparison) static const int methodsLengths[] = { 3,9,7,4,16,14,11,18,4,11,4,21,4,5,18,12,16,13,12, 7,7,11,19,23,20,14,14,18,18,5,11,2,12,18,9,21,12,19 }; static const int absCentralFirst = 0; static const int absCentralLast = 7; static const int absNoncentralFirst = 8; static const int absNoncentralLast = 11; static const int upnpIndex = 12; static const int relCentralFirst = 13; static const int relCentralLast = 28; static const int relNoncentralFirst = 29; static const int relNoncentralLast = 35; static const int pointCloudFirst = 36; static const int pointCloudLast = 37; // The number of methods (needed for comparison) static const int numberMethods = pointCloudLast + 1; enum Method { P2P, P3P_KNEIP, P3P_GAO, EPNP, P3P_KNEIP_RANSAC, P3P_GAO_RANSAC, EPNP_RANSAC, ABS_NONLIN_CENTRAL, GP3P, GP3P_RANSAC, GPNP, ABS_NONLIN_NONCENTRAL, UPNP, TWOPT, TWOPT_ROTATIONONLY, ROTATIONONLY, FIVEPT_STEWENIUS, FIVEPT_NISTER, FIVEPT_KNEIP, SEVENPT, EIGHTPT, EIGENSOLVER, ROTATIONONLY_RANSAC, FIVEPT_STEWENIUS_RANSAC, FIVEPT_NISTER_RANSAC, SEVENPT_RANSAC, EIGHTPT_RANSAC, EIGENSOLVER_RANSAC, REL_NONLIN_CENTRAL, SIXPT, SEVENTEENPT, GE, SIXPT_RANSAC, SEVENTEENPT_RANSAC, GE_RANSAC, REL_NONLIN_NONCENTRAL, THREEPT_ARUN, THREEPT_ARUN_RANSAC }; // Finds the method based on string comparison int findCase( const char* input, int inputLength ) { int n = 0; while( n < numberMethods ) { // First check the length of the string, it needs to be same if( inputLength == methodsLengths[n]) { // Now check if all the elements are the same int allSame = 1; for( int i = 0; i < inputLength; i++ ) { if( input[i] != methods[n][i] ) { allSame = 0; break; } } // Break if method found if( allSame ) return n; //Otherwise go on with the next one } n++; } // Return -1 if not found return -1; } // Print all possible cases void printCases() { mexPrintf("The known methods are:"); for( int i = 0; i < numberMethods; i++ ) { mexPrintf("\n"); mexPrintf(methods[i]); } mexPrintf("\n"); } typedef opengv::sac_problems::absolute_pose::AbsolutePoseSacProblem absRansac; typedef std::shared_ptr absRansacPtr; typedef opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem relRansac; typedef std::shared_ptr relRansacPtr; typedef opengv::sac_problems::relative_pose::NoncentralRelativePoseSacProblem nrelRansac; typedef std::shared_ptr nrelRansacPtr; typedef opengv::sac_problems::relative_pose::RotationOnlySacProblem rotRansac; typedef std::shared_ptr rotRansacPtr; typedef opengv::sac_problems::relative_pose::EigensolverSacProblem eigRansac; typedef std::shared_ptr eigRansacPtr; typedef opengv::sac_problems::point_cloud::PointCloudSacProblem ptRansac; typedef std::shared_ptr ptRansacPtr; // The main mex-function void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] ) { int numberIterations = 20; // Check if right number of arguments if( nrhs < 3 || nrhs > 5 ) { mexPrintf("opengv: Not an acceptable number of arguments\n"); mexPrintf("Usage: X = opengv( method, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2, prior )\n"); return; } // Get the method if( mxGetM(prhs[0]) != 1 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Usage: X = opengv( method, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2 )\n"); mexPrintf("Or: X = opengv( method, indices, data1, data2, prior )\n"); mexPrintf("Hint: Method must be a string\n"); return; } // Now get the string and find the caseNumber mwSize strlen = (mwSize) mxGetN(prhs[0]) + 1; char * method = (char *) malloc(strlen); mxGetString(prhs[0], method, strlen); int caseNumber = findCase(method, (int) mxGetN(prhs[0])); // Return if method not found if( caseNumber < 0 ) { mexPrintf("opengv: Unknown method\n"); printCases(); return; } // Characterize the type of the call int callCharacter = -1; const mxArray *data1; const mxArray *data2; const mwSize *data1dim; const mwSize *data2dim; if( nrhs == 3 ) // X = opengv( method, data1, data2 ) { // Check the input data1 = prhs[1]; data2 = prhs[2]; // Check the dimensions of the arguments int ndimensions1 = mxGetNumberOfDimensions(data1); int ndimensions2 = mxGetNumberOfDimensions(data2); data1dim = mxGetDimensions(data1); data2dim = mxGetDimensions(data2); // Now check them if( ndimensions1 != 2 || ndimensions2 != 2 || (data1dim[0] != 3 && data1dim[0] != 6) || (data2dim[0] != 3 && data2dim[0] != 6) || data1dim[1] != data2dim[1] || data1dim[1] < 1 || data2dim[1] < 1 ) { mexPrintf("opengv: Bad input to mex function\n"); mexPrintf("Assuming signature: X = opengv( method, data1, data2 )\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) or (6,n),\n"); mexPrintf("where n is the number of correspondences\n"); return; } callCharacter = 0; } if( nrhs == 4 ) { // X = opengv( method, indices, data1, data2 ) // Check the input data1 = prhs[2]; data2 = prhs[3]; // Check the dimensions of the arguments int ndimensions1 = mxGetNumberOfDimensions(data1); int ndimensions2 = mxGetNumberOfDimensions(data2); int ndimensions3 = mxGetNumberOfDimensions(prhs[1]); data1dim = mxGetDimensions(data1); data2dim = mxGetDimensions(data2); const mwSize *indicesDim = mxGetDimensions(prhs[1]); // Now check them if( ndimensions1 != 2 || ndimensions2 != 2 || ndimensions3 != 2 || (data1dim[0] != 3 && data1dim[0] != 6) || (data2dim[0] != 3 && data2dim[0] != 6) || indicesDim[0] != 1 || data1dim[1] != data2dim[1] || data1dim[1] < 1 || data2dim[1] < 1 || data2dim[1] < indicesDim[1] ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming signature: X = opengv( method, indices, data1, "); mexPrintf("data2 )\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) or (6,n),\n"); mexPrintf("where n is the number of correspondences\n"); mexPrintf("indices must be a 1xm vector, with m smaller or equal than n\n"); return; } callCharacter = 1; } if(nrhs == 5) { // X = opengv( method, indices, data1, data2, prior ) // Check the input data1 = prhs[2]; data2 = prhs[3]; // Check the dimensions of the arguments int ndimensions1 = mxGetNumberOfDimensions(data1); int ndimensions2 = mxGetNumberOfDimensions(data2); int ndimensions3 = mxGetNumberOfDimensions(prhs[1]); int ndimensions4 = mxGetNumberOfDimensions(prhs[4]); data1dim = mxGetDimensions(data1); data2dim = mxGetDimensions(data2); const mwSize *indicesDim = mxGetDimensions(prhs[1]); const mwSize *priorDim = mxGetDimensions(prhs[4]); // Now check them if( ndimensions1 != 2 || ndimensions2 != 2 || ndimensions3 != 2 || ndimensions4 != 2 || (data1dim[0] != 3 && data1dim[0] != 6) || (data2dim[0] != 3 && data2dim[0] != 6) || indicesDim[0] != 1 || priorDim[0] != 3 || (priorDim[1] != 1 && priorDim[1] != 3 && priorDim[1] != 4) || data1dim[1] != data2dim[1] || data1dim[1] < 1 || data2dim[1] < 1 || data2dim[1] < indicesDim[1] ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming signature: X = opengv( method, indices, data1, "); mexPrintf("data2, prior )\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) or (6,n),\n"); mexPrintf("where n is the number of correspondences\n"); mexPrintf("indices must be a 1xm vector, with m smaller or equal than n\n"); mexPrintf("prior must be a 3x1, 3x3, or 3x4 matrix\n"); return; } callCharacter = 2; } //create three pointers to absolute, relative, and point_cloud adapters here opengv::absolute_pose::AbsoluteAdapterBase* absoluteAdapter; opengv::relative_pose::RelativeAdapterBase* relativeAdapter; opengv::point_cloud::PointCloudAdapterBase* pointCloudAdapter; int translationPrior = 0; int rotationPrior = 0; opengv::translation_t translation; opengv::rotation_t rotation; //set the prior if needed if( callCharacter == 2 ) { const mxArray *prior; const mwSize *priorDim; prior = prhs[4]; priorDim = mxGetDimensions(prhs[4]); if( priorDim[1] == 1 ) { //set translation translationPrior = 1; double * ptr = (double*) mxGetData(prior); translation[0] = ptr[0]; translation[1] = ptr[1]; translation[2] = ptr[2]; } if( priorDim[1] == 3 ) { //set rotation rotationPrior = 1; double * ptr = (double*) mxGetData(prior); rotation(0,0) = ptr[0]; rotation(1,0) = ptr[1]; rotation(2,0) = ptr[2]; rotation(0,1) = ptr[3]; rotation(1,1) = ptr[4]; rotation(2,1) = ptr[5]; rotation(0,2) = ptr[6]; rotation(1,2) = ptr[7]; rotation(2,2) = ptr[8]; } if( priorDim[1] == 4 ) { translationPrior = 1; rotationPrior = 1; double * ptr = (double*) mxGetData(prior); rotation(0,0) = ptr[0]; rotation(1,0) = ptr[1]; rotation(2,0) = ptr[2]; rotation(0,1) = ptr[3]; rotation(1,1) = ptr[4]; rotation(2,1) = ptr[5]; rotation(0,2) = ptr[6]; rotation(1,2) = ptr[7]; rotation(2,2) = ptr[8]; translation[0] = ptr[9]; translation[1] = ptr[10]; translation[2] = ptr[11]; } } if( caseNumber >= absCentralFirst && caseNumber <= absCentralLast ) { //central absolute case if( data1dim[0] != 3 || data2dim[0] != 3 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) for a central "); mexPrintf("absolute method\n"); return; } absoluteAdapter = new opengv::absolute_pose::MACentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) absoluteAdapter->sett(translation); if( rotationPrior == 1 ) absoluteAdapter->setR(rotation); } if( caseNumber >= absNoncentralFirst && caseNumber <= absNoncentralLast ) { //non-central absolute case if( data1dim[0] != 3 || data2dim[0] != 6 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have sizes (3,n) and (6,n) for "); mexPrintf("a noncentral absolute method\n"); return; } absoluteAdapter = new opengv::absolute_pose::MANoncentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) absoluteAdapter->sett(translation); if( rotationPrior == 1 ) absoluteAdapter->setR(rotation); } if( caseNumber == upnpIndex ) { if( data1dim[0] != 3 || (data2dim[0] != 3 && data2dim[0] != 6) ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have sizes (3,n) and (3,n) or (6,n) for "); mexPrintf("upnp\n"); return; } if( data2dim[0] == 3 ) { absoluteAdapter = new opengv::absolute_pose::MACentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); } else { absoluteAdapter = new opengv::absolute_pose::MANoncentralAbsolute( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); } if( translationPrior == 1 ) absoluteAdapter->sett(translation); if( rotationPrior == 1 ) absoluteAdapter->setR(rotation); } if( caseNumber >= relCentralFirst && caseNumber <= relCentralLast ) { //central relative case if( data1dim[0] != 3 || data2dim[0] != 3 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) for a central "); mexPrintf("relative method\n"); return; } relativeAdapter = new opengv::relative_pose::MACentralRelative( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) relativeAdapter->sett12(translation); if( rotationPrior == 1 ) relativeAdapter->setR12(rotation); } if(caseNumber >= relNoncentralFirst && caseNumber <= relNoncentralLast ) { //noncentral relative case if( data1dim[0] != 6 || data2dim[0] != 6 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (6,n) for a "); mexPrintf("noncentral relative method\n"); return; } relativeAdapter = new opengv::relative_pose::MANoncentralRelative( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) relativeAdapter->sett12(translation); if( rotationPrior == 1 ) relativeAdapter->setR12(rotation); } if(caseNumber >= pointCloudFirst && caseNumber <= pointCloudLast ) { //point-cloud case if( data1dim[0] != 3 || data2dim[0] != 3 ) { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("Inputs data1 and data2 must have size (3,n) for a "); mexPrintf("point-cloud method\n"); return; } pointCloudAdapter = new opengv::point_cloud::MAPointCloud( (double*) mxGetData(data1), (double*) mxGetData(data2), data1dim[1], data2dim[1] ); if( translationPrior == 1 ) pointCloudAdapter->sett12(translation); if( rotationPrior == 1 ) pointCloudAdapter->setR12(rotation); } //check if a return argument is needed, otherwise we won't start computing if( nlhs != 1 && nlhs != 2 ) { if( nlhs > 2 ) mexPrintf("opengv: Returns one or two variables!\n"); return; } //create the indices array (todo: check if there is a smarter way for doing this) std::vector indices; int useIndices = 0; if( callCharacter > 0 ) { useIndices = 1; const mwSize *indicesDim = mxGetDimensions(prhs[1]); int numberOfIndices = indicesDim[1]; indices.reserve(numberOfIndices); double * mxIndices = (double*) mxGetData(prhs[1]); for( int i = 0; i < numberOfIndices; i++ ) indices.push_back(floor(mxIndices[i]+0.01)-1); } Method methodEnum = static_cast(caseNumber); if( caseNumber != (int) methodEnum ) { mexPrintf("opengv: This method is not yet implemented!\n"); return; } // Finally, call the respective algorithm switch (methodEnum) { case P2P: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::translation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::p2p(*absoluteAdapter,indices); else temp = opengv::absolute_pose::p2p(*absoluteAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 1; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 3*sizeof(double)); break; } case P3P_KNEIP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::p3p_kneip(*absoluteAdapter,indices); else temp = opengv::absolute_pose::p3p_kneip(*absoluteAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case P3P_GAO: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::p3p_gao(*absoluteAdapter,indices); else temp = opengv::absolute_pose::p3p_gao(*absoluteAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case EPNP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::epnp(*absoluteAdapter,indices); else temp = opengv::absolute_pose::epnp(*absoluteAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case P3P_KNEIP_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::KNEIP, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::KNEIP ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case P3P_GAO_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GAO, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GAO ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case EPNP_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::EPNP, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::EPNP ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case ABS_NONLIN_CENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; opengv::translation_t starting_position = absoluteAdapter->gett(); opengv::rotation_t starting_rotation = absoluteAdapter->getR(); for( int i = 0; i < numberIterations; i++ ) { //reset the starting value absoluteAdapter->sett(starting_position); absoluteAdapter->setR(starting_rotation); if(useIndices) temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter,indices); else temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case GP3P: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::gp3p(*absoluteAdapter,indices); else temp = opengv::absolute_pose::gp3p(*absoluteAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case GP3P_RANSAC: { absRansacPtr problem; if(useIndices) problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GP3P, indices ) ); else problem = absRansacPtr( new absRansac( *absoluteAdapter, absRansac::GP3P ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0)*0.5/800.0)); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case GPNP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::gpnp(*absoluteAdapter,indices); else temp = opengv::absolute_pose::gpnp(*absoluteAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case ABS_NONLIN_NONCENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; opengv::translation_t starting_position = absoluteAdapter->gett(); opengv::rotation_t starting_rotation = absoluteAdapter->getR(); for( int i = 0; i < numberIterations; i++ ) { //reset the starting value absoluteAdapter->sett(starting_position); absoluteAdapter->setR(starting_rotation); if(useIndices) temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter,indices); else temp = opengv::absolute_pose::optimize_nonlinear(*absoluteAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case UPNP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformations_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::absolute_pose::upnp(*absoluteAdapter,indices); else temp = opengv::absolute_pose::upnp(*absoluteAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 4; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*12*sizeof(double); memcpy(targetAddress, temp[i].data(), 12*sizeof(double)); } break; } case TWOPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::translation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::twopt(*relativeAdapter,false,indices); else temp = opengv::relative_pose::twopt(*relativeAdapter,false); } mwSize dims[2]; dims[0] = 3; dims[1] = 1; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 3*sizeof(double)); break; } case TWOPT_ROTATIONONLY: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::twopt_rotationOnly(*relativeAdapter,indices); else temp = opengv::relative_pose::twopt_rotationOnly(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case ROTATIONONLY: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::rotationOnly(*relativeAdapter,indices); else temp = opengv::relative_pose::rotationOnly(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case FIVEPT_STEWENIUS: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::complexEssentials_t temp2; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp2 = opengv::relative_pose::fivept_stewenius(*relativeAdapter,indices); else temp2 = opengv::relative_pose::fivept_stewenius(*relativeAdapter); } opengv::essentials_t temp; for(size_t i = 0; i < temp2.size(); i++) { opengv::essential_t essentialMatrix; for(size_t r = 0; r < 3; r++) { for(size_t c = 0; c < 3; c++) essentialMatrix(r,c) = temp2[i](r,c).real(); } temp.push_back(essentialMatrix); } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case FIVEPT_NISTER: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::essentials_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::fivept_nister(*relativeAdapter,indices); else temp = opengv::relative_pose::fivept_nister(*relativeAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case FIVEPT_KNEIP: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotations_t temp; if(useIndices) { for( int i = 0; i < numberIterations; i++ ) temp = opengv::relative_pose::fivept_kneip(*relativeAdapter,indices); } else { mexPrintf("opengv: Bad input to mex function opengv\n"); mexPrintf("Assuming method: "); mexPrintf(methods[caseNumber]); mexPrintf("\n"); mexPrintf("You must provide an indices vector\n"); break; } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case SEVENPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::essentials_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::sevenpt(*relativeAdapter,indices); else temp = opengv::relative_pose::sevenpt(*relativeAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case EIGHTPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::essential_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::eightpt(*relativeAdapter,indices); else temp = opengv::relative_pose::eightpt(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case EIGENSOLVER: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; opengv::rotation_t starting_rotation = relativeAdapter->getR12(); for( int i = 0; i < numberIterations; i++ ) { relativeAdapter->setR12(starting_rotation); if(useIndices) temp = opengv::relative_pose::eigensolver(*relativeAdapter,indices); else temp = opengv::relative_pose::eigensolver(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 9*sizeof(double)); break; } case ROTATIONONLY_RANSAC: { rotRansacPtr problem; if(useIndices) problem = rotRansacPtr( new rotRansac( *relativeAdapter, indices ) ); else problem = rotRansacPtr( new rotRansac( *relativeAdapter ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 9*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case FIVEPT_STEWENIUS_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::STEWENIUS, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::STEWENIUS ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); opengv::transformation_t optimizedModel; problem->optimizeModelCoefficients(ransac.inliers_,ransac.model_coefficients_,optimizedModel); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); //memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); memcpy(mxGetData(plhs[0]), optimizedModel.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case FIVEPT_NISTER_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::NISTER, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::NISTER ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case SEVENPT_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::SEVENPT, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::SEVENPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case EIGHTPT_RANSAC: { relRansacPtr problem; if(useIndices) problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::EIGHTPT, indices ) ); else problem = relRansacPtr( new relRansac( *relativeAdapter, relRansac::EIGHTPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case EIGENSOLVER_RANSAC: { eigRansacPtr problem; if(useIndices) problem = eigRansacPtr( new eigRansac( *relativeAdapter, 10, indices ) ); else problem = eigRansacPtr( new eigRansac( *relativeAdapter, 10 ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 1.0; ransac.max_iterations_ = 50; ransac.computeModel(); opengv::transformation_t temp; temp.block<3,3>(0,0) = ransac.model_coefficients_.rotation; temp.block<3,1>(0,3) = ransac.model_coefficients_.translation; mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case REL_NONLIN_CENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; opengv::translation_t starting_position = relativeAdapter->gett12(); opengv::rotation_t starting_rotation = relativeAdapter->getR12(); for( int i = 0; i < numberIterations; i++ ) { //reset the starting value relativeAdapter->sett12(starting_position); relativeAdapter->setR12(starting_rotation); if(useIndices) temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter,indices); else temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case SIXPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotations_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::sixpt(*relativeAdapter,indices); else temp = opengv::relative_pose::sixpt(*relativeAdapter); } mwSize dims[3]; dims[0] = 3; dims[1] = 3; dims[2] = temp.size(); plhs[0] = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); for( int i = 0; i < temp.size(); i++ ) { void * targetAddress = ((char*) mxGetData(plhs[0])) + i*9*sizeof(double); memcpy(targetAddress, temp[i].data(), 9*sizeof(double)); } break; } case SEVENTEENPT: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::relative_pose::seventeenpt(*relativeAdapter,indices); else temp = opengv::relative_pose::seventeenpt(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case GE: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::rotation_t temp; opengv::rotation_t starting_rotation = relativeAdapter->getR12(); opengv::geOutput_t output;; for( int i = 0; i < numberIterations; i++ ) { output.rotation = starting_rotation; relativeAdapter->setR12(starting_rotation); if(useIndices) temp = opengv::relative_pose::ge(*relativeAdapter,indices,output); else temp = opengv::relative_pose::ge(*relativeAdapter,output); } mwSize dims[2]; dims[0] = 3; dims[1] = 3; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]),temp.data(), 9*sizeof(double)); break; } case SIXPT_RANSAC: { nrelRansacPtr problem; if(useIndices) problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SIXPT, indices ) ); else problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SIXPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case SEVENTEENPT_RANSAC: { nrelRansacPtr problem; if(useIndices) problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SEVENTEENPT, indices ) ); else problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SEVENTEENPT ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case GE_RANSAC: { nrelRansacPtr problem; if(useIndices) problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::GE, indices ) ); else problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::GE ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } case REL_NONLIN_NONCENTRAL: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; opengv::translation_t starting_position = relativeAdapter->gett12(); opengv::rotation_t starting_rotation = relativeAdapter->getR12(); for( int i = 0; i < numberIterations; i++ ) { //reset the starting value relativeAdapter->sett12(starting_position); relativeAdapter->setR12(starting_rotation); if(useIndices) temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter,indices); else temp = opengv::relative_pose::optimize_nonlinear(*relativeAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case THREEPT_ARUN: { if(nlhs > 1) { mexPrintf("opengv: method "); mexPrintf(methods[caseNumber]); mexPrintf(" returns only one parameter."); return; } opengv::transformation_t temp; for( int i = 0; i < numberIterations; i++ ) { if(useIndices) temp = opengv::point_cloud::threept_arun(*pointCloudAdapter,indices); else temp = opengv::point_cloud::threept_arun(*pointCloudAdapter); } mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), temp.data(), 12*sizeof(double)); break; } case THREEPT_ARUN_RANSAC: { ptRansacPtr problem; if(useIndices) problem = ptRansacPtr( new ptRansac( *pointCloudAdapter, indices ) ); else problem = ptRansacPtr( new ptRansac( *pointCloudAdapter ) ); opengv::sac::Ransac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 0.1; ransac.max_iterations_ = 50; ransac.computeModel(); mwSize dims[2]; dims[0] = 3; dims[1] = 4; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), ransac.model_coefficients_.data(), 12*sizeof(double)); if(nlhs > 1) { //fill the second return variable with the inliers std::vector inliers = ransac.inliers_; for( int i = 0; i < inliers.size(); i++ ) inliers[i] += 1; dims[0] = 1; dims[1] = inliers.size(); plhs[1] = mxCreateNumericArray(2, dims, mxINT32_CLASS, mxREAL); memcpy(mxGetData(plhs[1]), (void*) &(inliers[0]), inliers.size()*sizeof(int)); } break; } default: //-1 { // impossible break; } } } opengv/matlab/benchmark_relative_pose_noncentral_execution_times.m0000664016516101651610000000305113344612246025006 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 4; % Getting 10 points, and testing all algorithms with the respective number of points pt_number = 50; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 iterations iterations = 1000; % The algorithms we want to test algorithms = { 'seventeenpt' }; % This defines the number of points used for every algorithm indices = { [1:1:17] }; % The name of the algorithms in the final plots names = { '17pt' }; % The noise in this experiment noise = 1.0; %% Run the benchmark %prepare the overall result arrays num_algorithms = size(algorithms,1); execution_times = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; for a=1:num_algorithms tic Out = opengv_donotuse(algorithms{a},indices{a},v1,v2,T_perturbed); execution_times(a,i) = toc/20.0; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %% Plot the results hist(execution_times') legend(names,'Location','NorthWest') xlabel('execution times [s]') grid on mean(execution_times') opengv/matlab/plot_ge_costfunction.m0000664016516101651610000001103213344612246016651 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % noncentral case cam_number = 4; % Getting 20 points pt_number = 20; % no outliers outlier_fraction = 0.0; % no noise noise = 0.0; [v1,v2,t,R] = create2D2DOmniExperiment(pt_number,cam_number,noise,outlier_fraction); %% Plot the smallest Eigenvalue evs = zeros(101,101); for cay_z_index=1:5 cay_z = (cay_z_index - 3) * 0.2; cay_z_index for i=1:101 cay_x = 0.4*((i-51)/50); i for j=1:101 cay_y = 0.4*((j-51) / 50); x = [cay_x;cay_y;cay_z]; if i == 51 && j == 51 && cay_z_index == 3 cay_y = 0.4*((52-51) / 50); x = [cay_x;cay_y;cay_z]; end Out = opengv('ge2',[1:1:size(v1,2)],v1,v2,[cayley2rot(x) zeros(3,1)]); evs(i,j) = Out(4,5); end end negativeIndices = evs<0; evs(negativeIndices) = 0.0; figure(1) hold on surf([-0.4 0.4],[-0.4 0.4],repmat(cay_z, [2 2]),log(evs),'facecolor','texture') %colormap(gray); view(45,30); daspect([2.5 2.5 1]); axis([-0.4 0.4 -0.4 0.4 -0.4 0.4]) grid on xlabel('x'); ylabel('y'); zlabel('z'); colorbar end %% insert the zero layer insertZeroLayer = 0; if insertZeroLayer == 1 gt = rot2cayley(R); cay_z = gt(3,1); for i=1:101 cay_x = 0.4*((i-51)/50); i for j=1:101 cay_y = 0.4*((j-51) / 50); x = [cay_x;cay_y;cay_z]; if i == 51 && j == 51 && cay_z_index == 3 cay_y = 0.4*((52-51) / 50); x = [cay_x;cay_y;cay_z]; end Out = opengv('ge2',[1:1:size(v1,2)],v1,v2,[cayley2rot(x) zeros(3,1)]); evs(i,j) = Out(4,5); end end negativeIndices = evs<0; evs(negativeIndices) = 0.0; figure(1) hold on surf([-0.4 0.4],[-0.4 0.4],repmat(cay_z, [2 2]),log(evs),'facecolor','texture') %colormap(gray); view(45,30); daspect([2.5 2.5 1]); axis([-0.4 0.4 -0.4 0.4 -0.4 0.4]) grid on xlabel('x'); ylabel('y'); zlabel('z'); colorbar end %% Plot the second smallest Eigenvalue evs = zeros(101,101); for cay_z_index=1:5 cay_z = (cay_z_index - 3) * 0.2; cay_z_index for i=1:101 cay_x = 0.4*((i-51)/50); i for j=1:101 cay_y = 0.4*((j-51) / 50); x = [cay_x;cay_y;cay_z]; if i == 51 && j == 51 && cay_z_index == 3 cay_y = 0.4*((52-51) / 50); x = [cay_x;cay_y;cay_z]; end Out = opengv('ge2',[1:1:size(v1,2)],v1,v2,[cayley2rot(x) zeros(3,1)]); evs(i,j) = Out(3,5); end end negativeIndices = evs<0; evs(negativeIndices) = 0.0; figure(2) hold on surf([-0.4 0.4],[-0.4 0.4],repmat(cay_z, [2 2]),log(evs),'facecolor','texture') %colormap(gray); view(45,30); daspect([2.5 2.5 1]); axis([-0.4 0.4 -0.4 0.4 -0.4 0.4]) grid on xlabel('x'); ylabel('y'); zlabel('z'); colorbar end %% insert the zero layer insertZeroLayer = 0; if insertZeroLayer == 1 gt = rot2cayley(R); cay_z = gt(3,1); for i=1:101 cay_x = 0.4*((i-51)/50); i for j=1:101 cay_y = 0.4*((j-51) / 50); x = [cay_x;cay_y;cay_z]; if i == 51 && j == 51 && cay_z_index == 3 cay_y = 0.4*((52-51) / 50); x = [cay_x;cay_y;cay_z]; end Out = opengv('ge2',[1:1:size(v1,2)],v1,v2,[cayley2rot(x) zeros(3,1)]); evs(i,j) = Out(3,5); end end negativeIndices = evs<0; evs(negativeIndices) = 0.0; figure(2) hold on surf([-0.4 0.4],[-0.4 0.4],repmat(cay_z, [2 2]),log(evs),'facecolor','texture') %colormap(gray); view(45,30); daspect([2.5 2.5 1]); axis([-0.4 0.4 -0.4 0.4 -0.4 0.4]) grid on xlabel('x'); ylabel('y'); zlabel('z'); colorbar end %% Print the ground truth value on the console minimum = rot2cayley(R)opengv/matlab/benchmark_relative_pose_noncentral2.m0000664016516101651610000000631513344612246021612 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % noncentral case cam_number = 4; % Getting 17 points, and testing all algorithms with the respective number of points pt_number = 17; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 tests per noise level iterations = 1000; % The algorithms we want to test algorithms = { 'sixpt'; 'ge'; 'ge'; 'seventeenpt'; 'rel_nonlin_noncentral' }; % This defines the number of points used for every algorithm indices = { [1:1:6]; [1:1:8]; [1:1:17]; [1:1:17]; [1:1:17] }; % The name of the algorithms in the final plots names = { '6pt'; 'ge (8pt)'; 'ge (17pt)'; '17pt'; 'nonlin. opt. (17pt)' }; % The maximum noise to analyze max_noise = 5.0; % The step in between different noise levels noise_step = 0.1; %% Run the benchmark %prepare the overall result arrays number_noise_levels = max_noise / noise_step + 1; num_algorithms = size(algorithms,1); mean_rotation_errors = zeros(num_algorithms,number_noise_levels); median_rotation_errors = zeros(num_algorithms,number_noise_levels); noise_levels = zeros(1,number_noise_levels); %Run the experiment for n=1:number_noise_levels noise = (n - 1) * noise_step; noise_levels(1,n) = noise; display(['Analyzing noise level: ' num2str(noise)]) rotation_errors = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DOmniExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; T_init = [eye(3),zeros(3,1)]; T_gt = [R,t]; for a=1:num_algorithms if strcmp(algorithms{a},'ge') Out = opengv(algorithms{a},indices{a},v1,v2,T_init); else Out = opengv(algorithms{a},indices{a},v1,v2,T_perturbed); end if a > 3 %if a bigger than 4, we obtain entire transformation, and need to "cut" the rotation temp = Out(:,1:3); Out = temp; end rotation_error = evaluateRotationError( R, Out ); rotation_errors(a,i) = rotation_error; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms mean_rotation_errors(a,n) = mean(rotation_errors(a,:)); median_rotation_errors(a,n) = median(rotation_errors(a,:)); end end %% Plot the results figure(1) plot(noise_levels,mean_rotation_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean rot. error [rad]') grid on figure(2) plot(noise_levels,median_rotation_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median rot. error [rad]') grid onopengv/matlab/benchmark_relative_pose_execution_times.m0000664016516101651610000000344513344612246022572 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 1; % Getting 10 points, and testing all algorithms with the respective number of points pt_number = 10; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 iterations iterations = 1000; % The algorithms we want to test algorithms = { 'twopt';'fivept_stewenius'; 'fivept_nister'; 'fivept_kneip'; 'sevenpt'; 'eightpt'; 'eigensolver' }; % This defines the number of points used for every algorithm indices = { [1,2]; [1, 2, 3, 4, 5]; [1, 2, 3, 4, 5]; [1, 2, 3, 4, 5]; [1, 2, 3, 4, 5, 6, 7]; [1, 2, 3, 4, 5, 6, 7, 8]; [1, 2, 3, 4, 5, 6, 7, 8, 9, 10] }; % The name of the algorithms in the final plots names = { '2pt';'5pt (Stewenius)'; '5pt (Nister)'; '5pt (Kneip)'; '7pt'; '8pt'; 'eigensolver' }; % noise in this experiment noise = 1.0; %% Run the benchmark %prepare the overall result arrays num_algorithms = size(algorithms,1); execution_times = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; for a=1:num_algorithms tic Out = opengv_donotuse(algorithms{a},indices{a},v1,v2,T_perturbed); execution_times(a,i) = toc/20.0; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations)]); end end %% Plot the results hist(execution_times') legend(names,'Location','NorthWest') xlabel('execution times [s]') grid on mean(execution_times') opengv/matlab/benchmark_relative_pose_noncentral_execution_times2.m0000664016516101651610000000455413344612246025101 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % central case -> only one camera cam_number = 4; % Getting 17 points, and testing all algorithms with the respective number of points pt_number = 17; % noise test, so no outliers outlier_fraction = 0.0; % repeat 1000 iterations iterations = 1000; % The algorithms we want to test algorithms = { 'sixpt'; 'ge'; 'seventeenpt' }; % This defines the number of points used for every algorithm indices = { [1:1:6]; [1:1:8]; [1:1:17] }; % The name of the algorithms in the final plots names = { '6pt';'ge (8pt)'; '17pt' }; % The noise in this experiment noise = 0.5; %% Run the benchmark %prepare the overall result arrays num_algorithms = size(algorithms,1); execution_times = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DOmniExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; T_init = [eye(3) zeros(3,1)]; for a=1:num_algorithms tic Out = opengv_donotuse(algorithms{a},indices{a},v1,v2,T_init); execution_times(a,i) = toc/20.0; end counter = counter + 1; if counter == 1 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %% Plot results hist(log10(execution_times)') legend(names,'Location','NorthWest') xlabel('execution time [s]') ylabel('occurence') grid on %% print the mean and median execution time on the console display( 'mean execution times:' ) display(['sixpt: ' num2str(mean(execution_times(1,:)'))] ); display(['ge: ' num2str(mean(execution_times(2,:)'))] ); display(['seventeenpt: ' num2str(mean(execution_times(3,:)'))] ); %% Plot the results % % [y1,x1] = hist(execution_times(1,:)); % [y2,x2] = hist(execution_times(2,:)); % [y3,x3] = hist(execution_times(3,:)); % % y1 = y1 / (x1(1,2) - x1(1,1)); % y2 = y2 / (x2(1,2) - x2(1,1)); % y3 = y3 / (x3(1,2) - x3(1,1)); % % figure(2) % hold on % plot(x1,y1,'b'); % plot(x2,y2,'g'); % plot(x3,y3,'r'); % legend(names,'Location','NorthWest') % xlabel('execution time [s]') % ylabel('probability') % grid on opengv/matlab/ransac_experiment.m0000664016516101651610000000415513344612246016141 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % noncentral case cam_number = 4; % set maximum and minimum number of points per cam pt_number_per_cam = 50; % set maximum and minimum number of outliers min_outlier_fraction = 0.1; max_outlier_fraction = 0.2; % repeat 10000 iterations iterations = 1000; % The name of the algorithms in the final plots names = { 'Homogeneous'; 'Vanilla' }; % The noise in this experiment noise = 0.5; %% Run the benchmark %prepare the overall result arrays ransac_iterations = zeros(2,iterations); %Run the RANSAC with homogeneous sampling counter = 0; for i=1:iterations %generate random outlier fraction outlier_fraction = rand() * (max_outlier_fraction - min_outlier_fraction) + min_outlier_fraction; % generate experiment [v1,v2,cam_offsets,t,R] = createMulti2D2DExperiment(pt_number_per_cam,cam_number,noise,outlier_fraction); Out = opengv_experimental1( v1{1,1}, v1{2,1}, v1{3,1}, v1{4,1}, v2{1,1}, v2{2,1}, v2{3,1}, v2{4,1}, cam_offsets, 2 ); ransac_iterations(1,i) = Out(1,5); counter = counter + 1; if counter == 100 counter = 0; display(['Homogeneous sampling: Iteration ' num2str(i) ' of ' num2str(iterations)]); end end %Run the RANSAC with vanilla sampling counter = 0; for i=1:iterations %generate random outlier fraction outlier_fraction = rand() * (max_outlier_fraction - min_outlier_fraction) + min_outlier_fraction; % generate experiment [v1,v2,t,R] = create2D2DExperiment(pt_number_per_cam*cam_number,cam_number,noise,outlier_fraction); Out = opengv_experimental2( v1, v2, 2 ); ransac_iterations(2,i) = Out(1,5); counter = counter + 1; if counter == 100 counter = 0; display(['Vanilla sampling: Iteration ' num2str(i) ' of ' num2str(iterations)]); end end %% Plot the results figure(1) hist(ransac_iterations') [Y,X] = hist(ransac_iterations') legend(names,'Location','NorthEast') xlabel('number of iterations') grid onopengv/matlab/benchmark_relative_pose_noncentral.m0000664016516101651610000000700613344612246021526 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % noncentral case cam_number = 4; % Getting 10 points, and testing all algorithms with the respective number of points pt_number = 50; % noise test, so no outliers outlier_fraction = 0.0; % repeat 5000 tests per noise level iterations = 5000; % The algorithms we want to test algorithms = { 'seventeenpt'; 'rel_nonlin_noncentral'; 'rel_nonlin_noncentral' }; % This defines the number of points used for every algorithm indices = { [1:1:17]; [1:1:17]; [1:1:50] }; % The name of the algorithms in the final plots names = { '17pt'; 'nonlin. opt. (17pts)'; 'nonlin. opt. (50pts)' }; % The maximum noise to analyze max_noise = 5.0; % The step in between different noise levels noise_step = 0.1; %% Run the benchmark %prepare the overall result arrays number_noise_levels = max_noise / noise_step + 1; num_algorithms = size(algorithms,1); mean_rotation_errors = zeros(num_algorithms,number_noise_levels); median_rotation_errors = zeros(num_algorithms,number_noise_levels); mean_position_errors = zeros(num_algorithms,number_noise_levels); median_position_errors = zeros(num_algorithms,number_noise_levels); noise_levels = zeros(1,number_noise_levels); %Run the experiment for n=1:number_noise_levels noise = (n - 1) * noise_step; noise_levels(1,n) = noise; display(['Analyzing noise level: ' num2str(noise)]) rotation_errors = zeros(num_algorithms,iterations); position_errors = zeros(num_algorithms,iterations); counter = 0; for i=1:iterations % generate experiment [v1,v2,t,R] = create2D2DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; T_gt = [R,t]; for a=1:num_algorithms Out = opengv(algorithms{a},indices{a},v1,v2,T_perturbed); [position_error, rotation_error] = evaluateTransformationError( T_gt, Out ); position_errors(a,i) = position_error; rotation_errors(a,i) = rotation_error; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms mean_rotation_errors(a,n) = mean(rotation_errors(a,:)); median_rotation_errors(a,n) = median(rotation_errors(a,:)); mean_position_errors(a,n) = mean(position_errors(a,:)); median_position_errors(a,n) = median(position_errors(a,:)); end end %% Plot the results figure(1) plot(noise_levels,mean_rotation_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean rot. error [rad]') grid on figure(2) plot(noise_levels,median_rotation_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median rot. error [rad]') grid on figure(3) plot(noise_levels,mean_position_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean pos. error [m]') grid on figure(4) plot(noise_levels,median_position_errors,'LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median pos. error [m]') grid onopengv/matlab/ransac_experiment2.m0000664016516101651610000000556313344612246016227 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); rng shuffle %% Configure the benchmark % noncentral case cam_number = 4; % Getting 10 points, and testing all algorithms with the respective number of points pt_per_cam = 20; % outlier test, so constant noise noise = 0.5; % repeat 100 tests per outlier-ratio iterations = 50; % The algorithms we want to test algorithms = [ 0; 1; 2 ]; % The name of the algorithms in the final plots names = { '6pt'; 'ge (8pt)'; '17pt'}; % The main experiment parameters min_outlier_fraction = 0.05; max_outlier_fraction = 0.45; outlier_fraction_step = 0.05; %% Run the benchmark %prepare the overall result arrays number_outlier_fraction_levels = round((max_outlier_fraction - min_outlier_fraction) / outlier_fraction_step + 1); num_algorithms = size(algorithms,1); %Run the experiment for n=1:number_outlier_fraction_levels outlier_fraction = (n - 1) * outlier_fraction_step + min_outlier_fraction; display(['Analyzing outlier fraction level: ' num2str(outlier_fraction)]) clear number_iterations clear execution_times counter = 0; temp_file_name1 = ['number_iterations_' num2str(outlier_fraction) '.mat']; temp_file_name2 = ['execution_times_' num2str(outlier_fraction) '.mat']; if exist(temp_file_name1,'file') > 0 display(['number_iterations_' num2str(outlier_fraction) '.mat exists already']) load(temp_file_name1) load(temp_file_name2) startingIteration = size(number_iterations,2) + 1; display(['starting at ' num2str(startingIteration)]) else startingIteration = 1; end if startingIteration <= iterations for i=startingIteration:iterations % generate experiment [v1,v2,cam_offsets,t,R] = createMulti2D2DOmniExperiment(pt_per_cam,cam_number,noise,outlier_fraction); for a=1:num_algorithms if strcmp(names{a,1},'6pt') && outlier_fraction > 0.25 Out = zeros(4,5); time = 10000000.0; else tic Out = opengv_experimental1( v1{1,1}, v1{2,1}, v1{3,1}, v1{4,1}, v2{1,1}, v2{2,1}, v2{3,1}, v2{4,1}, cam_offsets, algorithms(a,1) ); time = toc; end number_iterations(a,i) = Out(1,5); execution_times(a,i) = time; end save(temp_file_name1,'number_iterations'); save(temp_file_name2,'execution_times'); counter = counter + 1; if counter == 1 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(outlier_fraction level ' num2str(outlier_fraction) ')']); end end end endopengv/matlab/benchmark_absolute_pose_noncentral.m0000664016516101651610000001007613344612246021532 0ustar dimadima%% Reset everything clear all; clc; close all; addpath('helpers'); %% Configure the benchmark % noncentral case cam_number = 4; % let's only get 6 points, and generate new ones in each iteration pt_number = 50; % noise test, so no outliers outlier_fraction = 0.0; % repeat 5000 iterations per noise level iterations = 5000; % The algorithms we want to test algorithms = { 'gp3p'; 'gpnp'; 'gpnp'; 'abs_nonlin_noncentral'; 'abs_nonlin_noncentral'; 'upnp'; 'upnp' }; % This defines the number of points used for every algorithm indices = { [1, 2, 3]; [1:1:10]; [1:1:50]; [1:1:10]; [1:1:50]; [1:1:10]; [1:1:50] }; % The name of the algorithms on the plots names = { 'GP3P'; 'GPnP (10pts)'; 'GPnP (50pts)'; 'nonlin. opt. (10pts)'; 'nonlin. opt. (50pts)'; 'UPnP (10pts)'; 'UPnP (50pts)' }; % The maximum noise to analyze max_noise = 5.0; % The step in between different noise levels noise_step = 0.1; %% Run the benchmark %prepare the overall result arrays number_noise_levels = max_noise / noise_step + 1; num_algorithms = size(algorithms,1); mean_position_errors = zeros(num_algorithms,number_noise_levels); mean_rotation_errors = zeros(num_algorithms,number_noise_levels); median_position_errors = zeros(num_algorithms,number_noise_levels); median_rotation_errors = zeros(num_algorithms,number_noise_levels); noise_levels = zeros(1,number_noise_levels); %Run the experiment for n=1:number_noise_levels noise = (n - 1) * noise_step; noise_levels(1,n) = noise; display(['Analyzing noise level: ' num2str(noise)]) position_errors = zeros(num_algorithms,iterations); rotation_errors = zeros(num_algorithms,iterations); counter = 0; validIterations = 0; for i=1:iterations % generate experiment [points,v,t,R] = create2D3DExperiment(pt_number,cam_number,noise,outlier_fraction); [t_perturbed,R_perturbed] = perturb(t,R,0.01); T_perturbed = [R_perturbed,t_perturbed]; T_gt = [R,t]; % run all algorithms allValid = 1; for a=1:num_algorithms T = opengv(algorithms{a},indices{a},points,v,T_perturbed); [position_error, rotation_error] = evaluateTransformationError( T_gt, T ); if( position_error > 100 ) allValid = 0; break; else position_errors(a,validIterations+1) = position_error; rotation_errors(a,validIterations+1) = rotation_error; end end if allValid == 1 validIterations = validIterations +1; end counter = counter + 1; if counter == 100 counter = 0; display(['Iteration ' num2str(i) ' of ' num2str(iterations) '(noise level ' num2str(noise) ')']); end end %Now compute the mean and median value of the error for each algorithm for a=1:num_algorithms mean_position_errors(a,n) = mean(position_errors(a,1:validIterations)); median_position_errors(a,n) = median(position_errors(a,1:validIterations)); mean_rotation_errors(a,n) = mean(rotation_errors(a,1:validIterations)); median_rotation_errors(a,n) = median(rotation_errors(a,1:validIterations)); end end %% Plot the results figure(1) plot(noise_levels',mean_rotation_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean rot. error [rad]') grid on figure(2) plot(noise_levels',median_rotation_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median rot. error [rad]') grid on figure(3) plot(noise_levels',mean_position_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('mean pos. error [m]') grid on figure(4) plot(noise_levels',median_position_errors','LineWidth',2) legend(names,'Location','NorthWest') xlabel('noise level [pix]') ylabel('median pos. error [m]') grid onopengv/matlab/opengv_experimental1.cpp0000664016516101651610000001265213344612246017115 0ustar dimadimastatic const char *copyright = " Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved."; /****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ // Matlab usage: // // X = opengv_experimental1( data11, data12, data13, ..., data21, data22, data23, ..., camOffsets, algorithm ) // // where // data1x and data2x are matched points (each one of dimension 3xn) // camOffsets is a 3xn matrix, with being the number of cameras // algorithm is 0 for sixpt, 1 for ge, and 2 for seventeenpt // X is a 3x5 matrix returning the found transformation, plus the number of // Ransac-iterations and inliers // //matlab header //standard headers #include #include #include #include "mex.h" //include generic headers for opengv stuff #include //include the matlab-adapter #include //expose all ransac-facilities to matlab #include #include typedef opengv::sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem nrelRansac; typedef std::shared_ptr nrelRansacPtr; // The main mex-function void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] ) { //no error-checking here yet, simply provide the right input!! //get number of cameras int numberCams = (nrhs-2)/2; const mxArray *camOffsets = prhs[nrhs-2]; const mxArray *temp1 = prhs[nrhs-1]; double *temp2 = (double*) mxGetData(temp1); int algorithm = floor(temp2[0]+0.01); std::vector bearingVectors1; std::vector bearingVectors2; std::vector numberBearingVectors; for( int cam = 0; cam < numberCams; cam++ ) { const mxArray *data1 = prhs[cam]; const mxArray *data2 = prhs[cam+numberCams]; bearingVectors1.push_back((double*) mxGetData(data1)); bearingVectors2.push_back((double*) mxGetData(data2)); const mwSize *dataDim = mxGetDimensions(data1); numberBearingVectors.push_back(dataDim[1]); } opengv::relative_pose::RelativeMultiAdapterBase* relativeAdapter = new opengv::relative_pose::MANoncentralRelativeMulti( bearingVectors1, bearingVectors2, (double*) mxGetData(camOffsets), numberBearingVectors ); nrelRansacPtr problem; switch(algorithm) { case 0: problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SIXPT ) ); break; case 1: problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::GE ) ); break; case 2: problem = nrelRansacPtr( new nrelRansac( *relativeAdapter, nrelRansac::SEVENTEENPT ) ); break; } opengv::sac::MultiRansac ransac; ransac.sac_model_ = problem; ransac.threshold_ = 2.0*(1.0 - cos(atan(sqrt(2.0)*0.5/800.0))); ransac.max_iterations_ = 10000000; ransac.computeModel(); Eigen::Matrix result; result.block<3,4>(0,0) = ransac.model_coefficients_; result(0,4) = ransac.iterations_; result(1,4) = ransac.inliers_.size(); int dims[2]; dims[0] = 3; dims[1] = 5; plhs[0] = mxCreateNumericArray(2, dims, mxDOUBLE_CLASS, mxREAL); memcpy(mxGetData(plhs[0]), result.data(), 15*sizeof(double)); } opengv/src/0000775016516101651610000000000013344612246011576 5ustar dimadimaopengv/src/point_cloud/0000775016516101651610000000000013344612246014115 5ustar dimadimaopengv/src/point_cloud/methods.cpp0000664016516101651610000001500013344612246016260 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include namespace opengv { namespace point_cloud { transformation_t threept_arun( const PointCloudAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 2); //derive the centroid of the two point-clouds point_t pointsCenter1 = Eigen::Vector3d::Zero(); point_t pointsCenter2 = Eigen::Vector3d::Zero(); for( size_t i = 0; i < numberCorrespondences; i++ ) { pointsCenter1 += adapter.getPoint1(indices[i]); pointsCenter2 += adapter.getPoint2(indices[i]); } pointsCenter1 = pointsCenter1 / numberCorrespondences; pointsCenter2 = pointsCenter2 / numberCorrespondences; //compute the matrix H = sum(f'*f^{T}) Eigen::MatrixXd Hcross(3,3); Hcross = Eigen::Matrix3d::Zero(); for( size_t i = 0; i < numberCorrespondences; i++ ) { Eigen::Vector3d f = adapter.getPoint1(indices[i]) - pointsCenter1; Eigen::Vector3d fprime = adapter.getPoint2(indices[i]) - pointsCenter2; Hcross += fprime * f.transpose(); } //decompose this matrix (SVD) to obtain rotation rotation_t rotation = math::arun(Hcross); translation_t translation = pointsCenter1 - rotation*pointsCenter2; transformation_t solution; solution.block<3,3>(0,0) = rotation; solution.col(3) = translation; return solution; }; } } opengv::transformation_t opengv::point_cloud::threept_arun( const PointCloudAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return threept_arun(adapter,idx); }; opengv::transformation_t opengv::point_cloud::threept_arun( const PointCloudAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return threept_arun(adapter,idx); }; namespace opengv { namespace point_cloud { struct OptimizeNonlinearFunctor1 : OptimizationFunctor { PointCloudAdapterBase & _adapter; const Indices & _indices; OptimizeNonlinearFunctor1( PointCloudAdapterBase & adapter, const Indices & indices ) : OptimizationFunctor(6,indices.size()), _adapter(adapter), _indices(indices) {} int operator()(const VectorXd &x, VectorXd &fvec) const { assert( x.size() == 6 ); assert( (unsigned int) fvec.size() == _indices.size()); //compute the current position transformation_t transformation; transformation.col(3) = x.block<3,1>(0,0); cayley_t cayley = x.block<3,1>(3,0); transformation.block<3,3>(0,0) = math::cayley2rot(cayley); Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < _indices.size(); i++ ) { p_hom.block<3,1>(0,0) = _adapter.getPoint2(_indices[i]); point_t transformedPoint = transformation * p_hom; translation_t error = _adapter.getPoint1(_indices[i]) - transformedPoint; fvec[i] = error.norm(); } return 0; } }; transformation_t optimize_nonlinear( PointCloudAdapterBase & adapter, const Indices & indices ) { const int n=6; VectorXd x(n); x.block<3,1>(0,0) = adapter.gett12(); x.block<3,1>(3,0) = math::rot2cayley(adapter.getR12()); OptimizeNonlinearFunctor1 functor( adapter, indices ); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 1.E10*NumTraits::epsilon(); lm.parameters.xtol = 1.E10*NumTraits::epsilon(); lm.parameters.maxfev = 1000; lm.minimize(x); transformation_t transformation; transformation.col(3) = x.block<3,1>(0,0); transformation.block<3,3>(0,0) = math::cayley2rot(x.block<3,1>(3,0)); return transformation; } } } opengv::transformation_t opengv::point_cloud::optimize_nonlinear( PointCloudAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return optimize_nonlinear(adapter,idx); } opengv::transformation_t opengv::point_cloud::optimize_nonlinear( PointCloudAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return optimize_nonlinear(adapter,idx); } opengv/src/point_cloud/MAPointCloud.cpp0000664016516101651610000000664013344612246017125 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::point_cloud::MAPointCloud::MAPointCloud( const double * points1, const double * points2, int numberPoints1, int numberPoints2 ) : PointCloudAdapterBase(), _points1(points1), _points2(points2), _numberPoints1(numberPoints1), _numberPoints2(numberPoints2) {} opengv::point_cloud::MAPointCloud::~MAPointCloud() {} opengv::point_t opengv::point_cloud::MAPointCloud:: getPoint1( size_t index ) const { point_t point; assert( index < _numberPoints1 ); point[0] = _points1[ 3 * index]; point[1] = _points1[ 3 * index + 1]; point[2] = _points1[ 3 * index + 2]; return point; } opengv::point_t opengv::point_cloud::MAPointCloud:: getPoint2( size_t index ) const { assert(index < _numberPoints2); point_t point; point[0] = _points2[ index * 3 ]; point[1] = _points2[ index * 3 + 1 ]; point[2] = _points2[ index * 3 + 2 ]; return point; } double opengv::point_cloud::MAPointCloud:: getWeight( size_t index ) const { return 1.0; } size_t opengv::point_cloud::MAPointCloud:: getNumberCorrespondences() const { return _numberPoints2; } opengv/src/point_cloud/PointCloudAdapter.cpp0000664016516101651610000000713213344612246020205 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::point_cloud::PointCloudAdapter::PointCloudAdapter( const points_t & points1, const points_t & points2 ) : PointCloudAdapterBase(), _points1(points1), _points2(points2) {} opengv::point_cloud::PointCloudAdapter::PointCloudAdapter( const points_t & points1, const points_t & points2, const rotation_t & R12 ) : PointCloudAdapterBase(R12), _points1(points1), _points2(points2) {} opengv::point_cloud::PointCloudAdapter::PointCloudAdapter( const points_t & points1, const points_t & points2, const translation_t & t12, const rotation_t & R12 ) : PointCloudAdapterBase(t12,R12), _points1(points1), _points2(points2) {} opengv::point_cloud::PointCloudAdapter::~PointCloudAdapter() {} opengv::point_t opengv::point_cloud::PointCloudAdapter:: getPoint1( size_t index ) const { assert(index < _points1.size()); return _points1[index]; } opengv::point_t opengv::point_cloud::PointCloudAdapter:: getPoint2( size_t index ) const { assert(index < _points2.size()); return _points2[index]; } double opengv::point_cloud::PointCloudAdapter:: getWeight( size_t index ) const { return 1.0; } size_t opengv::point_cloud::PointCloudAdapter:: getNumberCorrespondences() const { return _points2.size(); } opengv/src/triangulation/0000775016516101651610000000000013344612246014456 5ustar dimadimaopengv/src/triangulation/methods.cpp0000664016516101651610000001027513344612246016632 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include opengv::point_t opengv::triangulation::triangulate( const relative_pose::RelativeAdapterBase & adapter, size_t index ) { translation_t t12 = adapter.gett12(); rotation_t R12 = adapter.getR12(); Eigen::Matrix P1 = Eigen::Matrix::Zero(); P1.block<3,3>(0,0) = Eigen::Matrix3d::Identity(); Eigen::Matrix P2 = Eigen::Matrix::Zero(); P2.block<3,3>(0,0) = R12.transpose(); P2.block<3,1>(0,3) = -R12.transpose()*t12; bearingVector_t f1 = adapter.getBearingVector1(index); bearingVector_t f2 = adapter.getBearingVector2(index); Eigen::MatrixXd A(4,4); A.row(0) = f1[0] * P1.row(2) - f1[2] * P1.row(0); A.row(1) = f1[1] * P1.row(2) - f1[2] * P1.row(1); A.row(2) = f2[0] * P2.row(2) - f2[2] * P2.row(0); A.row(3) = f2[1] * P2.row(2) - f2[2] * P2.row(1); Eigen::JacobiSVD< Eigen::MatrixXd > mySVD(A, Eigen::ComputeFullV ); point_t worldPoint; worldPoint[0] = mySVD.matrixV()(0,3); worldPoint[1] = mySVD.matrixV()(1,3); worldPoint[2] = mySVD.matrixV()(2,3); worldPoint = worldPoint / mySVD.matrixV()(3,3); return worldPoint; }; opengv::point_t opengv::triangulation::triangulate2( const relative_pose::RelativeAdapterBase & adapter, size_t index ) { translation_t t12 = adapter.gett12(); rotation_t R12 = adapter.getR12(); bearingVector_t f1 = adapter.getBearingVector1(index); bearingVector_t f2 = adapter.getBearingVector2(index); bearingVector_t f2_unrotated = R12 * f2; Eigen::Vector2d b; b[0] = t12.dot(f1); b[1] = t12.dot(f2_unrotated); Eigen::Matrix2d A; A(0,0) = f1.dot(f1); A(1,0) = f1.dot(f2_unrotated); A(0,1) = -A(1,0); A(1,1) = -f2_unrotated.dot(f2_unrotated); Eigen::Vector2d lambda = A.inverse() * b; Eigen::Vector3d xm = lambda[0] * f1; Eigen::Vector3d xn = t12 + lambda[1] * f2_unrotated; point_t point = ( xm + xn )/2; return point; }; opengv/src/relative_pose/0000775016516101651610000000000013344612246014437 5ustar dimadimaopengv/src/relative_pose/modules/0000775016516101651610000000000014257362435016115 5ustar dimadimaopengv/src/relative_pose/modules/sixpt/0000775016516101651610000000000013344612246017256 5ustar dimadimaopengv/src/relative_pose/modules/sixpt/modules2.cpp0000664016516101651610000120163413344612246021523 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include void opengv::relative_pose::modules::sixpt::fillRow1( const Eigen::Matrix & l01, const Eigen::Matrix & l02, const Eigen::Matrix & l11, const Eigen::Matrix & l12, std::vector & c0, std::vector & c1, std::vector & c2 ) { c0.push_back(-l12[2]*l11[1]*l01[0]+l12[2]*l11[0]*l01[1]+l12[1]*l11[2]*l01[0]-l12[1]*l11[0]*l01[2]+l12[0]*l11[2]*l01[1]-l12[0]*l11[1]*l01[2]); c0.push_back(2*l12[1]*l11[2]*l01[1]-2*l12[1]*l11[1]*l01[2]-2*l12[0]*l11[2]*l01[0]+2*l12[0]*l11[0]*l01[2]); c0.push_back(-l12[2]*l11[1]*l01[0]+l12[2]*l11[0]*l01[1]-l12[1]*l11[2]*l01[0]+l12[1]*l11[0]*l01[2]-l12[0]*l11[2]*l01[1]+l12[0]*l11[1]*l01[2]); c0.push_back(2*l12[2]*l11[2]*l01[1]-2*l12[2]*l11[1]*l01[2]+2*l12[0]*l11[1]*l01[0]-2*l12[0]*l11[0]*l01[1]); c0.push_back(-2*l12[2]*l11[2]*l01[0]+2*l12[2]*l11[0]*l01[2]+2*l12[1]*l11[1]*l01[0]-2*l12[1]*l11[0]*l01[1]); c0.push_back(l12[2]*l11[1]*l01[0]-l12[2]*l11[0]*l01[1]+l12[1]*l11[2]*l01[0]-l12[1]*l11[0]*l01[2]-l12[0]*l11[2]*l01[1]+l12[0]*l11[1]*l01[2]); c0.push_back(-2*l12[2]*l11[2]*l01[0]+2*l12[2]*l11[0]*l01[2]-2*l12[1]*l11[1]*l01[0]+2*l12[1]*l11[0]*l01[1]); c0.push_back(-2*l12[2]*l11[2]*l01[1]+2*l12[2]*l11[1]*l01[2]+2*l12[0]*l11[1]*l01[0]-2*l12[0]*l11[0]*l01[1]); c0.push_back(2*l12[1]*l11[2]*l01[1]-2*l12[1]*l11[1]*l01[2]+2*l12[0]*l11[2]*l01[0]-2*l12[0]*l11[0]*l01[2]); c0.push_back(l12[2]*l11[1]*l01[0]-l12[2]*l11[0]*l01[1]-l12[1]*l11[2]*l01[0]+l12[1]*l11[0]*l01[2]+l12[0]*l11[2]*l01[1]-l12[0]*l11[1]*l01[2]); c1.push_back(l12[2]*l11[1]*l02[0]+l12[2]*l11[0]*l02[1]-l12[1]*l11[2]*l02[0]-l12[1]*l11[0]*l02[2]+l12[0]*l11[2]*l02[1]-l12[0]*l11[1]*l02[2]); c1.push_back(2*l12[2]*l11[1]*l02[1]-2*l12[2]*l11[0]*l02[0]-2*l12[1]*l11[1]*l02[2]+2*l12[0]*l11[0]*l02[2]); c1.push_back(-l12[2]*l11[1]*l02[0]-l12[2]*l11[0]*l02[1]-l12[1]*l11[2]*l02[0]+l12[1]*l11[0]*l02[2]+l12[0]*l11[2]*l02[1]+l12[0]*l11[1]*l02[2]); c1.push_back(2*l12[2]*l11[2]*l02[1]-2*l12[1]*l11[2]*l02[2]+2*l12[1]*l11[0]*l02[0]-2*l12[0]*l11[0]*l02[1]); c1.push_back(-2*l12[2]*l11[2]*l02[0]+2*l12[1]*l11[1]*l02[0]+2*l12[0]*l11[2]*l02[2]-2*l12[0]*l11[1]*l02[1]); c1.push_back(l12[2]*l11[1]*l02[0]-l12[2]*l11[0]*l02[1]+l12[1]*l11[2]*l02[0]+l12[1]*l11[0]*l02[2]-l12[0]*l11[2]*l02[1]-l12[0]*l11[1]*l02[2]); c1.push_back(2*l12[2]*l11[2]*l02[0]+2*l12[1]*l11[1]*l02[0]-2*l12[0]*l11[2]*l02[2]-2*l12[0]*l11[1]*l02[1]); c1.push_back(2*l12[2]*l11[2]*l02[1]-2*l12[1]*l11[2]*l02[2]-2*l12[1]*l11[0]*l02[0]+2*l12[0]*l11[0]*l02[1]); c1.push_back(-2*l12[2]*l11[1]*l02[1]-2*l12[2]*l11[0]*l02[0]+2*l12[1]*l11[1]*l02[2]+2*l12[0]*l11[0]*l02[2]); c1.push_back(-l12[2]*l11[1]*l02[0]+l12[2]*l11[0]*l02[1]+l12[1]*l11[2]*l02[0]-l12[1]*l11[0]*l02[2]-l12[0]*l11[2]*l02[1]+l12[0]*l11[1]*l02[2]); c2.push_back(-l12[2]*l11[1]*l02[5]*l02[1]+l12[2]*l11[1]*l02[4]*l02[2]+l12[2]*l11[1]*l01[5]*l01[1]-l12[2]*l11[1]*l01[4]*l01[2]+l12[2]*l11[0]*l02[5]*l02[0]-l12[2]*l11[0]*l02[3]*l02[2]+l12[2]*l11[0]*l01[5]*l01[0]-l12[2]*l11[0]*l01[3]*l01[2]+l12[1]*l11[2]*l02[5]*l02[1]-l12[1]*l11[2]*l02[4]*l02[2]-l12[1]*l11[2]*l01[5]*l01[1]+l12[1]*l11[2]*l01[4]*l01[2]+l12[1]*l11[0]*l02[4]*l02[0]-l12[1]*l11[0]*l02[3]*l02[1]+l12[1]*l11[0]*l01[4]*l01[0]-l12[1]*l11[0]*l01[3]*l01[1]+l12[0]*l11[2]*l02[5]*l02[0]-l12[0]*l11[2]*l02[3]*l02[2]+l12[0]*l11[2]*l01[5]*l01[0]-l12[0]*l11[2]*l01[3]*l01[2]+l12[0]*l11[1]*l02[4]*l02[0]-l12[0]*l11[1]*l02[3]*l02[1]+l12[0]*l11[1]*l01[4]*l01[0]-l12[0]*l11[1]*l01[3]*l01[1]-l12[5]*l11[2]-l12[4]*l11[1]+l12[3]*l11[0]-l12[2]*l11[5]-l12[1]*l11[4]+l12[0]*l11[3]); c2.push_back(2*l12[2]*l11[1]*l02[5]*l02[0]-2*l12[2]*l11[1]*l02[3]*l02[2]+2*l12[2]*l11[0]*l02[5]*l02[1]-2*l12[2]*l11[0]*l02[4]*l02[2]+2*l12[1]*l11[2]*l01[5]*l01[0]-2*l12[1]*l11[2]*l01[3]*l01[2]+2*l12[1]*l11[1]*l02[4]*l02[0]-2*l12[1]*l11[1]*l02[3]*l02[1]+2*l12[1]*l11[1]*l01[4]*l01[0]-2*l12[1]*l11[1]*l01[3]*l01[1]+2*l12[0]*l11[2]*l01[5]*l01[1]-2*l12[0]*l11[2]*l01[4]*l01[2]-2*l12[0]*l11[0]*l02[4]*l02[0]+2*l12[0]*l11[0]*l02[3]*l02[1]-2*l12[0]*l11[0]*l01[4]*l01[0]+2*l12[0]*l11[0]*l01[3]*l01[1]+2*l12[4]*l11[0]+2*l12[3]*l11[1]+2*l12[1]*l11[3]+2*l12[0]*l11[4]); c2.push_back(l12[2]*l11[1]*l02[5]*l02[1]-l12[2]*l11[1]*l02[4]*l02[2]+l12[2]*l11[1]*l01[5]*l01[1]-l12[2]*l11[1]*l01[4]*l01[2]-l12[2]*l11[0]*l02[5]*l02[0]+l12[2]*l11[0]*l02[3]*l02[2]+l12[2]*l11[0]*l01[5]*l01[0]-l12[2]*l11[0]*l01[3]*l01[2]+l12[1]*l11[2]*l02[5]*l02[1]-l12[1]*l11[2]*l02[4]*l02[2]+l12[1]*l11[2]*l01[5]*l01[1]-l12[1]*l11[2]*l01[4]*l01[2]-l12[1]*l11[0]*l02[4]*l02[0]+l12[1]*l11[0]*l02[3]*l02[1]-l12[1]*l11[0]*l01[4]*l01[0]+l12[1]*l11[0]*l01[3]*l01[1]+l12[0]*l11[2]*l02[5]*l02[0]-l12[0]*l11[2]*l02[3]*l02[2]-l12[0]*l11[2]*l01[5]*l01[0]+l12[0]*l11[2]*l01[3]*l01[2]-l12[0]*l11[1]*l02[4]*l02[0]+l12[0]*l11[1]*l02[3]*l02[1]-l12[0]*l11[1]*l01[4]*l01[0]+l12[0]*l11[1]*l01[3]*l01[1]-l12[5]*l11[2]+l12[4]*l11[1]-l12[3]*l11[0]-l12[2]*l11[5]+l12[1]*l11[4]-l12[0]*l11[3]); c2.push_back(2*l12[2]*l11[2]*l02[5]*l02[0]-2*l12[2]*l11[2]*l02[3]*l02[2]+2*l12[2]*l11[2]*l01[5]*l01[0]-2*l12[2]*l11[2]*l01[3]*l01[2]+2*l12[2]*l11[1]*l01[4]*l01[0]-2*l12[2]*l11[1]*l01[3]*l01[1]+2*l12[1]*l11[2]*l02[4]*l02[0]-2*l12[1]*l11[2]*l02[3]*l02[1]-2*l12[1]*l11[0]*l02[5]*l02[1]+2*l12[1]*l11[0]*l02[4]*l02[2]-2*l12[0]*l11[1]*l01[5]*l01[1]+2*l12[0]*l11[1]*l01[4]*l01[2]-2*l12[0]*l11[0]*l02[5]*l02[0]+2*l12[0]*l11[0]*l02[3]*l02[2]-2*l12[0]*l11[0]*l01[5]*l01[0]+2*l12[0]*l11[0]*l01[3]*l01[2]+2*l12[5]*l11[0]+2*l12[3]*l11[2]+2*l12[2]*l11[3]+2*l12[0]*l11[5]); c2.push_back(2*l12[2]*l11[2]*l02[5]*l02[1]-2*l12[2]*l11[2]*l02[4]*l02[2]+2*l12[2]*l11[2]*l01[5]*l01[1]-2*l12[2]*l11[2]*l01[4]*l01[2]-2*l12[2]*l11[0]*l01[4]*l01[0]+2*l12[2]*l11[0]*l01[3]*l01[1]-2*l12[1]*l11[1]*l02[5]*l02[1]+2*l12[1]*l11[1]*l02[4]*l02[2]-2*l12[1]*l11[1]*l01[5]*l01[1]+2*l12[1]*l11[1]*l01[4]*l01[2]-2*l12[1]*l11[0]*l01[5]*l01[0]+2*l12[1]*l11[0]*l01[3]*l01[2]-2*l12[0]*l11[2]*l02[4]*l02[0]+2*l12[0]*l11[2]*l02[3]*l02[1]-2*l12[0]*l11[1]*l02[5]*l02[0]+2*l12[0]*l11[1]*l02[3]*l02[2]+2*l12[5]*l11[1]+2*l12[4]*l11[2]+2*l12[2]*l11[4]+2*l12[1]*l11[5]); c2.push_back(-l12[2]*l11[1]*l02[5]*l02[1]+l12[2]*l11[1]*l02[4]*l02[2]-l12[2]*l11[1]*l01[5]*l01[1]+l12[2]*l11[1]*l01[4]*l01[2]-l12[2]*l11[0]*l02[5]*l02[0]+l12[2]*l11[0]*l02[3]*l02[2]-l12[2]*l11[0]*l01[5]*l01[0]+l12[2]*l11[0]*l01[3]*l01[2]-l12[1]*l11[2]*l02[5]*l02[1]+l12[1]*l11[2]*l02[4]*l02[2]-l12[1]*l11[2]*l01[5]*l01[1]+l12[1]*l11[2]*l01[4]*l01[2]-l12[1]*l11[0]*l02[4]*l02[0]+l12[1]*l11[0]*l02[3]*l02[1]+l12[1]*l11[0]*l01[4]*l01[0]-l12[1]*l11[0]*l01[3]*l01[1]-l12[0]*l11[2]*l02[5]*l02[0]+l12[0]*l11[2]*l02[3]*l02[2]-l12[0]*l11[2]*l01[5]*l01[0]+l12[0]*l11[2]*l01[3]*l01[2]+l12[0]*l11[1]*l02[4]*l02[0]-l12[0]*l11[1]*l02[3]*l02[1]-l12[0]*l11[1]*l01[4]*l01[0]+l12[0]*l11[1]*l01[3]*l01[1]+l12[5]*l11[2]-l12[4]*l11[1]-l12[3]*l11[0]+l12[2]*l11[5]-l12[1]*l11[4]-l12[0]*l11[3]); c2.push_back(-2*l12[2]*l11[2]*l02[5]*l02[1]+2*l12[2]*l11[2]*l02[4]*l02[2]+2*l12[2]*l11[2]*l01[5]*l01[1]-2*l12[2]*l11[2]*l01[4]*l01[2]-2*l12[2]*l11[0]*l01[4]*l01[0]+2*l12[2]*l11[0]*l01[3]*l01[1]-2*l12[1]*l11[1]*l02[5]*l02[1]+2*l12[1]*l11[1]*l02[4]*l02[2]+2*l12[1]*l11[1]*l01[5]*l01[1]-2*l12[1]*l11[1]*l01[4]*l01[2]+2*l12[1]*l11[0]*l01[5]*l01[0]-2*l12[1]*l11[0]*l01[3]*l01[2]+2*l12[0]*l11[2]*l02[4]*l02[0]-2*l12[0]*l11[2]*l02[3]*l02[1]-2*l12[0]*l11[1]*l02[5]*l02[0]+2*l12[0]*l11[1]*l02[3]*l02[2]+2*l12[5]*l11[1]-2*l12[4]*l11[2]+2*l12[2]*l11[4]-2*l12[1]*l11[5]); c2.push_back(2*l12[2]*l11[2]*l02[5]*l02[0]-2*l12[2]*l11[2]*l02[3]*l02[2]-2*l12[2]*l11[2]*l01[5]*l01[0]+2*l12[2]*l11[2]*l01[3]*l01[2]-2*l12[2]*l11[1]*l01[4]*l01[0]+2*l12[2]*l11[1]*l01[3]*l01[1]+2*l12[1]*l11[2]*l02[4]*l02[0]-2*l12[1]*l11[2]*l02[3]*l02[1]+2*l12[1]*l11[0]*l02[5]*l02[1]-2*l12[1]*l11[0]*l02[4]*l02[2]-2*l12[0]*l11[1]*l01[5]*l01[1]+2*l12[0]*l11[1]*l01[4]*l01[2]+2*l12[0]*l11[0]*l02[5]*l02[0]-2*l12[0]*l11[0]*l02[3]*l02[2]-2*l12[0]*l11[0]*l01[5]*l01[0]+2*l12[0]*l11[0]*l01[3]*l01[2]-2*l12[5]*l11[0]+2*l12[3]*l11[2]-2*l12[2]*l11[3]+2*l12[0]*l11[5]); c2.push_back(-2*l12[2]*l11[1]*l02[5]*l02[0]+2*l12[2]*l11[1]*l02[3]*l02[2]+2*l12[2]*l11[0]*l02[5]*l02[1]-2*l12[2]*l11[0]*l02[4]*l02[2]+2*l12[1]*l11[2]*l01[5]*l01[0]-2*l12[1]*l11[2]*l01[3]*l01[2]-2*l12[1]*l11[1]*l02[4]*l02[0]+2*l12[1]*l11[1]*l02[3]*l02[1]+2*l12[1]*l11[1]*l01[4]*l01[0]-2*l12[1]*l11[1]*l01[3]*l01[1]-2*l12[0]*l11[2]*l01[5]*l01[1]+2*l12[0]*l11[2]*l01[4]*l01[2]-2*l12[0]*l11[0]*l02[4]*l02[0]+2*l12[0]*l11[0]*l02[3]*l02[1]+2*l12[0]*l11[0]*l01[4]*l01[0]-2*l12[0]*l11[0]*l01[3]*l01[1]+2*l12[4]*l11[0]-2*l12[3]*l11[1]+2*l12[1]*l11[3]-2*l12[0]*l11[4]); c2.push_back(l12[2]*l11[1]*l02[5]*l02[1]-l12[2]*l11[1]*l02[4]*l02[2]-l12[2]*l11[1]*l01[5]*l01[1]+l12[2]*l11[1]*l01[4]*l01[2]+l12[2]*l11[0]*l02[5]*l02[0]-l12[2]*l11[0]*l02[3]*l02[2]-l12[2]*l11[0]*l01[5]*l01[0]+l12[2]*l11[0]*l01[3]*l01[2]-l12[1]*l11[2]*l02[5]*l02[1]+l12[1]*l11[2]*l02[4]*l02[2]+l12[1]*l11[2]*l01[5]*l01[1]-l12[1]*l11[2]*l01[4]*l01[2]+l12[1]*l11[0]*l02[4]*l02[0]-l12[1]*l11[0]*l02[3]*l02[1]-l12[1]*l11[0]*l01[4]*l01[0]+l12[1]*l11[0]*l01[3]*l01[1]-l12[0]*l11[2]*l02[5]*l02[0]+l12[0]*l11[2]*l02[3]*l02[2]+l12[0]*l11[2]*l01[5]*l01[0]-l12[0]*l11[2]*l01[3]*l01[2]-l12[0]*l11[1]*l02[4]*l02[0]+l12[0]*l11[1]*l02[3]*l02[1]+l12[0]*l11[1]*l01[4]*l01[0]-l12[0]*l11[1]*l01[3]*l01[1]+l12[5]*l11[2]+l12[4]*l11[1]+l12[3]*l11[0]+l12[2]*l11[5]+l12[1]*l11[4]+l12[0]*l11[3]); } void opengv::relative_pose::modules::sixpt::fillRow2( Eigen::Matrix & M1, int row, const std::vector (&m0)[3], const std::vector (&m1)[3], const std::vector (&m2)[3] ) { M1(row,0) = m2[2][0]*m1[1][0]*m0[0][0]-m2[2][0]*m1[0][0]*m0[1][0]-m2[1][0]*m1[2][0]*m0[0][0]+m2[1][0]*m1[0][0]*m0[2][0]+m2[0][0]*m1[2][0]*m0[1][0]-m2[0][0]*m1[1][0]*m0[2][0]; M1(row,1) = m2[2][1]*m1[1][0]*m0[0][0]-m2[2][1]*m1[0][0]*m0[1][0]+m2[2][0]*m1[1][1]*m0[0][0]+m2[2][0]*m1[1][0]*m0[0][1]-m2[2][0]*m1[0][1]*m0[1][0]-m2[2][0]*m1[0][0]*m0[1][1]-m2[1][1]*m1[2][0]*m0[0][0]+m2[1][1]*m1[0][0]*m0[2][0]-m2[1][0]*m1[2][1]*m0[0][0]-m2[1][0]*m1[2][0]*m0[0][1]+m2[1][0]*m1[0][1]*m0[2][0]+m2[1][0]*m1[0][0]*m0[2][1]+m2[0][1]*m1[2][0]*m0[1][0]-m2[0][1]*m1[1][0]*m0[2][0]+m2[0][0]*m1[2][1]*m0[1][0]+m2[0][0]*m1[2][0]*m0[1][1]-m2[0][0]*m1[1][1]*m0[2][0]-m2[0][0]*m1[1][0]*m0[2][1]; M1(row,2) = m2[2][2]*m1[1][0]*m0[0][0]-m2[2][2]*m1[0][0]*m0[1][0]+m2[2][1]*m1[1][1]*m0[0][0]+m2[2][1]*m1[1][0]*m0[0][1]-m2[2][1]*m1[0][1]*m0[1][0]-m2[2][1]*m1[0][0]*m0[1][1]+m2[2][0]*m1[1][2]*m0[0][0]+m2[2][0]*m1[1][1]*m0[0][1]+m2[2][0]*m1[1][0]*m0[0][2]-m2[2][0]*m1[0][2]*m0[1][0]-m2[2][0]*m1[0][1]*m0[1][1]-m2[2][0]*m1[0][0]*m0[1][2]-m2[1][2]*m1[2][0]*m0[0][0]+m2[1][2]*m1[0][0]*m0[2][0]-m2[1][1]*m1[2][1]*m0[0][0]-m2[1][1]*m1[2][0]*m0[0][1]+m2[1][1]*m1[0][1]*m0[2][0]+m2[1][1]*m1[0][0]*m0[2][1]-m2[1][0]*m1[2][2]*m0[0][0]-m2[1][0]*m1[2][1]*m0[0][1]-m2[1][0]*m1[2][0]*m0[0][2]+m2[1][0]*m1[0][2]*m0[2][0]+m2[1][0]*m1[0][1]*m0[2][1]+m2[1][0]*m1[0][0]*m0[2][2]+m2[0][2]*m1[2][0]*m0[1][0]-m2[0][2]*m1[1][0]*m0[2][0]+m2[0][1]*m1[2][1]*m0[1][0]+m2[0][1]*m1[2][0]*m0[1][1]-m2[0][1]*m1[1][1]*m0[2][0]-m2[0][1]*m1[1][0]*m0[2][1]+m2[0][0]*m1[2][2]*m0[1][0]+m2[0][0]*m1[2][1]*m0[1][1]+m2[0][0]*m1[2][0]*m0[1][2]-m2[0][0]*m1[1][2]*m0[2][0]-m2[0][0]*m1[1][1]*m0[2][1]-m2[0][0]*m1[1][0]*m0[2][2]; M1(row,3) = m2[2][2]*m1[1][1]*m0[0][0]+m2[2][2]*m1[1][0]*m0[0][1]-m2[2][2]*m1[0][1]*m0[1][0]-m2[2][2]*m1[0][0]*m0[1][1]+m2[2][1]*m1[1][2]*m0[0][0]+m2[2][1]*m1[1][1]*m0[0][1]+m2[2][1]*m1[1][0]*m0[0][2]-m2[2][1]*m1[0][2]*m0[1][0]-m2[2][1]*m1[0][1]*m0[1][1]-m2[2][1]*m1[0][0]*m0[1][2]+m2[2][0]*m1[1][2]*m0[0][1]+m2[2][0]*m1[1][1]*m0[0][2]-m2[2][0]*m1[0][2]*m0[1][1]-m2[2][0]*m1[0][1]*m0[1][2]-m2[1][2]*m1[2][1]*m0[0][0]-m2[1][2]*m1[2][0]*m0[0][1]+m2[1][2]*m1[0][1]*m0[2][0]+m2[1][2]*m1[0][0]*m0[2][1]-m2[1][1]*m1[2][2]*m0[0][0]-m2[1][1]*m1[2][1]*m0[0][1]-m2[1][1]*m1[2][0]*m0[0][2]+m2[1][1]*m1[0][2]*m0[2][0]+m2[1][1]*m1[0][1]*m0[2][1]+m2[1][1]*m1[0][0]*m0[2][2]-m2[1][0]*m1[2][2]*m0[0][1]-m2[1][0]*m1[2][1]*m0[0][2]+m2[1][0]*m1[0][2]*m0[2][1]+m2[1][0]*m1[0][1]*m0[2][2]+m2[0][2]*m1[2][1]*m0[1][0]+m2[0][2]*m1[2][0]*m0[1][1]-m2[0][2]*m1[1][1]*m0[2][0]-m2[0][2]*m1[1][0]*m0[2][1]+m2[0][1]*m1[2][2]*m0[1][0]+m2[0][1]*m1[2][1]*m0[1][1]+m2[0][1]*m1[2][0]*m0[1][2]-m2[0][1]*m1[1][2]*m0[2][0]-m2[0][1]*m1[1][1]*m0[2][1]-m2[0][1]*m1[1][0]*m0[2][2]+m2[0][0]*m1[2][2]*m0[1][1]+m2[0][0]*m1[2][1]*m0[1][2]-m2[0][0]*m1[1][2]*m0[2][1]-m2[0][0]*m1[1][1]*m0[2][2]; M1(row,4) = m2[2][2]*m1[1][2]*m0[0][0]+m2[2][2]*m1[1][1]*m0[0][1]+m2[2][2]*m1[1][0]*m0[0][2]-m2[2][2]*m1[0][2]*m0[1][0]-m2[2][2]*m1[0][1]*m0[1][1]-m2[2][2]*m1[0][0]*m0[1][2]+m2[2][1]*m1[1][2]*m0[0][1]+m2[2][1]*m1[1][1]*m0[0][2]-m2[2][1]*m1[0][2]*m0[1][1]-m2[2][1]*m1[0][1]*m0[1][2]+m2[2][0]*m1[1][2]*m0[0][2]-m2[2][0]*m1[0][2]*m0[1][2]-m2[1][2]*m1[2][2]*m0[0][0]-m2[1][2]*m1[2][1]*m0[0][1]-m2[1][2]*m1[2][0]*m0[0][2]+m2[1][2]*m1[0][2]*m0[2][0]+m2[1][2]*m1[0][1]*m0[2][1]+m2[1][2]*m1[0][0]*m0[2][2]-m2[1][1]*m1[2][2]*m0[0][1]-m2[1][1]*m1[2][1]*m0[0][2]+m2[1][1]*m1[0][2]*m0[2][1]+m2[1][1]*m1[0][1]*m0[2][2]-m2[1][0]*m1[2][2]*m0[0][2]+m2[1][0]*m1[0][2]*m0[2][2]+m2[0][2]*m1[2][2]*m0[1][0]+m2[0][2]*m1[2][1]*m0[1][1]+m2[0][2]*m1[2][0]*m0[1][2]-m2[0][2]*m1[1][2]*m0[2][0]-m2[0][2]*m1[1][1]*m0[2][1]-m2[0][2]*m1[1][0]*m0[2][2]+m2[0][1]*m1[2][2]*m0[1][1]+m2[0][1]*m1[2][1]*m0[1][2]-m2[0][1]*m1[1][2]*m0[2][1]-m2[0][1]*m1[1][1]*m0[2][2]+m2[0][0]*m1[2][2]*m0[1][2]-m2[0][0]*m1[1][2]*m0[2][2]; M1(row,5) = m2[2][2]*m1[1][2]*m0[0][1]+m2[2][2]*m1[1][1]*m0[0][2]-m2[2][2]*m1[0][2]*m0[1][1]-m2[2][2]*m1[0][1]*m0[1][2]+m2[2][1]*m1[1][2]*m0[0][2]-m2[2][1]*m1[0][2]*m0[1][2]-m2[1][2]*m1[2][2]*m0[0][1]-m2[1][2]*m1[2][1]*m0[0][2]+m2[1][2]*m1[0][2]*m0[2][1]+m2[1][2]*m1[0][1]*m0[2][2]-m2[1][1]*m1[2][2]*m0[0][2]+m2[1][1]*m1[0][2]*m0[2][2]+m2[0][2]*m1[2][2]*m0[1][1]+m2[0][2]*m1[2][1]*m0[1][2]-m2[0][2]*m1[1][2]*m0[2][1]-m2[0][2]*m1[1][1]*m0[2][2]+m2[0][1]*m1[2][2]*m0[1][2]-m2[0][1]*m1[1][2]*m0[2][2]; M1(row,6) = m2[2][2]*m1[1][2]*m0[0][2]-m2[2][2]*m1[0][2]*m0[1][2]-m2[1][2]*m1[2][2]*m0[0][2]+m2[1][2]*m1[0][2]*m0[2][2]+m2[0][2]*m1[2][2]*m0[1][2]-m2[0][2]*m1[1][2]*m0[2][2]; M1(row,7) = m2[2][3]*m1[1][0]*m0[0][0]-m2[2][3]*m1[0][0]*m0[1][0]+m2[2][0]*m1[1][3]*m0[0][0]+m2[2][0]*m1[1][0]*m0[0][3]-m2[2][0]*m1[0][3]*m0[1][0]-m2[2][0]*m1[0][0]*m0[1][3]-m2[1][3]*m1[2][0]*m0[0][0]+m2[1][3]*m1[0][0]*m0[2][0]-m2[1][0]*m1[2][3]*m0[0][0]-m2[1][0]*m1[2][0]*m0[0][3]+m2[1][0]*m1[0][3]*m0[2][0]+m2[1][0]*m1[0][0]*m0[2][3]+m2[0][3]*m1[2][0]*m0[1][0]-m2[0][3]*m1[1][0]*m0[2][0]+m2[0][0]*m1[2][3]*m0[1][0]+m2[0][0]*m1[2][0]*m0[1][3]-m2[0][0]*m1[1][3]*m0[2][0]-m2[0][0]*m1[1][0]*m0[2][3]; M1(row,8) = m2[2][4]*m1[1][0]*m0[0][0]-m2[2][4]*m1[0][0]*m0[1][0]+m2[2][3]*m1[1][1]*m0[0][0]+m2[2][3]*m1[1][0]*m0[0][1]-m2[2][3]*m1[0][1]*m0[1][0]-m2[2][3]*m1[0][0]*m0[1][1]+m2[2][1]*m1[1][3]*m0[0][0]+m2[2][1]*m1[1][0]*m0[0][3]-m2[2][1]*m1[0][3]*m0[1][0]-m2[2][1]*m1[0][0]*m0[1][3]+m2[2][0]*m1[1][4]*m0[0][0]+m2[2][0]*m1[1][3]*m0[0][1]+m2[2][0]*m1[1][1]*m0[0][3]+m2[2][0]*m1[1][0]*m0[0][4]-m2[2][0]*m1[0][4]*m0[1][0]-m2[2][0]*m1[0][3]*m0[1][1]-m2[2][0]*m1[0][1]*m0[1][3]-m2[2][0]*m1[0][0]*m0[1][4]-m2[1][4]*m1[2][0]*m0[0][0]+m2[1][4]*m1[0][0]*m0[2][0]-m2[1][3]*m1[2][1]*m0[0][0]-m2[1][3]*m1[2][0]*m0[0][1]+m2[1][3]*m1[0][1]*m0[2][0]+m2[1][3]*m1[0][0]*m0[2][1]-m2[1][1]*m1[2][3]*m0[0][0]-m2[1][1]*m1[2][0]*m0[0][3]+m2[1][1]*m1[0][3]*m0[2][0]+m2[1][1]*m1[0][0]*m0[2][3]-m2[1][0]*m1[2][4]*m0[0][0]-m2[1][0]*m1[2][3]*m0[0][1]-m2[1][0]*m1[2][1]*m0[0][3]-m2[1][0]*m1[2][0]*m0[0][4]+m2[1][0]*m1[0][4]*m0[2][0]+m2[1][0]*m1[0][3]*m0[2][1]+m2[1][0]*m1[0][1]*m0[2][3]+m2[1][0]*m1[0][0]*m0[2][4]+m2[0][4]*m1[2][0]*m0[1][0]-m2[0][4]*m1[1][0]*m0[2][0]+m2[0][3]*m1[2][1]*m0[1][0]+m2[0][3]*m1[2][0]*m0[1][1]-m2[0][3]*m1[1][1]*m0[2][0]-m2[0][3]*m1[1][0]*m0[2][1]+m2[0][1]*m1[2][3]*m0[1][0]+m2[0][1]*m1[2][0]*m0[1][3]-m2[0][1]*m1[1][3]*m0[2][0]-m2[0][1]*m1[1][0]*m0[2][3]+m2[0][0]*m1[2][4]*m0[1][0]+m2[0][0]*m1[2][3]*m0[1][1]+m2[0][0]*m1[2][1]*m0[1][3]+m2[0][0]*m1[2][0]*m0[1][4]-m2[0][0]*m1[1][4]*m0[2][0]-m2[0][0]*m1[1][3]*m0[2][1]-m2[0][0]*m1[1][1]*m0[2][3]-m2[0][0]*m1[1][0]*m0[2][4]; M1(row,9) = m2[2][4]*m1[1][1]*m0[0][0]+m2[2][4]*m1[1][0]*m0[0][1]-m2[2][4]*m1[0][1]*m0[1][0]-m2[2][4]*m1[0][0]*m0[1][1]+m2[2][3]*m1[1][2]*m0[0][0]+m2[2][3]*m1[1][1]*m0[0][1]+m2[2][3]*m1[1][0]*m0[0][2]-m2[2][3]*m1[0][2]*m0[1][0]-m2[2][3]*m1[0][1]*m0[1][1]-m2[2][3]*m1[0][0]*m0[1][2]+m2[2][2]*m1[1][3]*m0[0][0]+m2[2][2]*m1[1][0]*m0[0][3]-m2[2][2]*m1[0][3]*m0[1][0]-m2[2][2]*m1[0][0]*m0[1][3]+m2[2][1]*m1[1][4]*m0[0][0]+m2[2][1]*m1[1][3]*m0[0][1]+m2[2][1]*m1[1][1]*m0[0][3]+m2[2][1]*m1[1][0]*m0[0][4]-m2[2][1]*m1[0][4]*m0[1][0]-m2[2][1]*m1[0][3]*m0[1][1]-m2[2][1]*m1[0][1]*m0[1][3]-m2[2][1]*m1[0][0]*m0[1][4]+m2[2][0]*m1[1][4]*m0[0][1]+m2[2][0]*m1[1][3]*m0[0][2]+m2[2][0]*m1[1][2]*m0[0][3]+m2[2][0]*m1[1][1]*m0[0][4]-m2[2][0]*m1[0][4]*m0[1][1]-m2[2][0]*m1[0][3]*m0[1][2]-m2[2][0]*m1[0][2]*m0[1][3]-m2[2][0]*m1[0][1]*m0[1][4]-m2[1][4]*m1[2][1]*m0[0][0]-m2[1][4]*m1[2][0]*m0[0][1]+m2[1][4]*m1[0][1]*m0[2][0]+m2[1][4]*m1[0][0]*m0[2][1]-m2[1][3]*m1[2][2]*m0[0][0]-m2[1][3]*m1[2][1]*m0[0][1]-m2[1][3]*m1[2][0]*m0[0][2]+m2[1][3]*m1[0][2]*m0[2][0]+m2[1][3]*m1[0][1]*m0[2][1]+m2[1][3]*m1[0][0]*m0[2][2]-m2[1][2]*m1[2][3]*m0[0][0]-m2[1][2]*m1[2][0]*m0[0][3]+m2[1][2]*m1[0][3]*m0[2][0]+m2[1][2]*m1[0][0]*m0[2][3]-m2[1][1]*m1[2][4]*m0[0][0]-m2[1][1]*m1[2][3]*m0[0][1]-m2[1][1]*m1[2][1]*m0[0][3]-m2[1][1]*m1[2][0]*m0[0][4]+m2[1][1]*m1[0][4]*m0[2][0]+m2[1][1]*m1[0][3]*m0[2][1]+m2[1][1]*m1[0][1]*m0[2][3]+m2[1][1]*m1[0][0]*m0[2][4]-m2[1][0]*m1[2][4]*m0[0][1]-m2[1][0]*m1[2][3]*m0[0][2]-m2[1][0]*m1[2][2]*m0[0][3]-m2[1][0]*m1[2][1]*m0[0][4]+m2[1][0]*m1[0][4]*m0[2][1]+m2[1][0]*m1[0][3]*m0[2][2]+m2[1][0]*m1[0][2]*m0[2][3]+m2[1][0]*m1[0][1]*m0[2][4]+m2[0][4]*m1[2][1]*m0[1][0]+m2[0][4]*m1[2][0]*m0[1][1]-m2[0][4]*m1[1][1]*m0[2][0]-m2[0][4]*m1[1][0]*m0[2][1]+m2[0][3]*m1[2][2]*m0[1][0]+m2[0][3]*m1[2][1]*m0[1][1]+m2[0][3]*m1[2][0]*m0[1][2]-m2[0][3]*m1[1][2]*m0[2][0]-m2[0][3]*m1[1][1]*m0[2][1]-m2[0][3]*m1[1][0]*m0[2][2]+m2[0][2]*m1[2][3]*m0[1][0]+m2[0][2]*m1[2][0]*m0[1][3]-m2[0][2]*m1[1][3]*m0[2][0]-m2[0][2]*m1[1][0]*m0[2][3]+m2[0][1]*m1[2][4]*m0[1][0]+m2[0][1]*m1[2][3]*m0[1][1]+m2[0][1]*m1[2][1]*m0[1][3]+m2[0][1]*m1[2][0]*m0[1][4]-m2[0][1]*m1[1][4]*m0[2][0]-m2[0][1]*m1[1][3]*m0[2][1]-m2[0][1]*m1[1][1]*m0[2][3]-m2[0][1]*m1[1][0]*m0[2][4]+m2[0][0]*m1[2][4]*m0[1][1]+m2[0][0]*m1[2][3]*m0[1][2]+m2[0][0]*m1[2][2]*m0[1][3]+m2[0][0]*m1[2][1]*m0[1][4]-m2[0][0]*m1[1][4]*m0[2][1]-m2[0][0]*m1[1][3]*m0[2][2]-m2[0][0]*m1[1][2]*m0[2][3]-m2[0][0]*m1[1][1]*m0[2][4]; M1(row,10) = m2[2][4]*m1[1][2]*m0[0][0]+m2[2][4]*m1[1][1]*m0[0][1]+m2[2][4]*m1[1][0]*m0[0][2]-m2[2][4]*m1[0][2]*m0[1][0]-m2[2][4]*m1[0][1]*m0[1][1]-m2[2][4]*m1[0][0]*m0[1][2]+m2[2][3]*m1[1][2]*m0[0][1]+m2[2][3]*m1[1][1]*m0[0][2]-m2[2][3]*m1[0][2]*m0[1][1]-m2[2][3]*m1[0][1]*m0[1][2]+m2[2][2]*m1[1][4]*m0[0][0]+m2[2][2]*m1[1][3]*m0[0][1]+m2[2][2]*m1[1][1]*m0[0][3]+m2[2][2]*m1[1][0]*m0[0][4]-m2[2][2]*m1[0][4]*m0[1][0]-m2[2][2]*m1[0][3]*m0[1][1]-m2[2][2]*m1[0][1]*m0[1][3]-m2[2][2]*m1[0][0]*m0[1][4]+m2[2][1]*m1[1][4]*m0[0][1]+m2[2][1]*m1[1][3]*m0[0][2]+m2[2][1]*m1[1][2]*m0[0][3]+m2[2][1]*m1[1][1]*m0[0][4]-m2[2][1]*m1[0][4]*m0[1][1]-m2[2][1]*m1[0][3]*m0[1][2]-m2[2][1]*m1[0][2]*m0[1][3]-m2[2][1]*m1[0][1]*m0[1][4]+m2[2][0]*m1[1][4]*m0[0][2]+m2[2][0]*m1[1][2]*m0[0][4]-m2[2][0]*m1[0][4]*m0[1][2]-m2[2][0]*m1[0][2]*m0[1][4]-m2[1][4]*m1[2][2]*m0[0][0]-m2[1][4]*m1[2][1]*m0[0][1]-m2[1][4]*m1[2][0]*m0[0][2]+m2[1][4]*m1[0][2]*m0[2][0]+m2[1][4]*m1[0][1]*m0[2][1]+m2[1][4]*m1[0][0]*m0[2][2]-m2[1][3]*m1[2][2]*m0[0][1]-m2[1][3]*m1[2][1]*m0[0][2]+m2[1][3]*m1[0][2]*m0[2][1]+m2[1][3]*m1[0][1]*m0[2][2]-m2[1][2]*m1[2][4]*m0[0][0]-m2[1][2]*m1[2][3]*m0[0][1]-m2[1][2]*m1[2][1]*m0[0][3]-m2[1][2]*m1[2][0]*m0[0][4]+m2[1][2]*m1[0][4]*m0[2][0]+m2[1][2]*m1[0][3]*m0[2][1]+m2[1][2]*m1[0][1]*m0[2][3]+m2[1][2]*m1[0][0]*m0[2][4]-m2[1][1]*m1[2][4]*m0[0][1]-m2[1][1]*m1[2][3]*m0[0][2]-m2[1][1]*m1[2][2]*m0[0][3]-m2[1][1]*m1[2][1]*m0[0][4]+m2[1][1]*m1[0][4]*m0[2][1]+m2[1][1]*m1[0][3]*m0[2][2]+m2[1][1]*m1[0][2]*m0[2][3]+m2[1][1]*m1[0][1]*m0[2][4]-m2[1][0]*m1[2][4]*m0[0][2]-m2[1][0]*m1[2][2]*m0[0][4]+m2[1][0]*m1[0][4]*m0[2][2]+m2[1][0]*m1[0][2]*m0[2][4]+m2[0][4]*m1[2][2]*m0[1][0]+m2[0][4]*m1[2][1]*m0[1][1]+m2[0][4]*m1[2][0]*m0[1][2]-m2[0][4]*m1[1][2]*m0[2][0]-m2[0][4]*m1[1][1]*m0[2][1]-m2[0][4]*m1[1][0]*m0[2][2]+m2[0][3]*m1[2][2]*m0[1][1]+m2[0][3]*m1[2][1]*m0[1][2]-m2[0][3]*m1[1][2]*m0[2][1]-m2[0][3]*m1[1][1]*m0[2][2]+m2[0][2]*m1[2][4]*m0[1][0]+m2[0][2]*m1[2][3]*m0[1][1]+m2[0][2]*m1[2][1]*m0[1][3]+m2[0][2]*m1[2][0]*m0[1][4]-m2[0][2]*m1[1][4]*m0[2][0]-m2[0][2]*m1[1][3]*m0[2][1]-m2[0][2]*m1[1][1]*m0[2][3]-m2[0][2]*m1[1][0]*m0[2][4]+m2[0][1]*m1[2][4]*m0[1][1]+m2[0][1]*m1[2][3]*m0[1][2]+m2[0][1]*m1[2][2]*m0[1][3]+m2[0][1]*m1[2][1]*m0[1][4]-m2[0][1]*m1[1][4]*m0[2][1]-m2[0][1]*m1[1][3]*m0[2][2]-m2[0][1]*m1[1][2]*m0[2][3]-m2[0][1]*m1[1][1]*m0[2][4]+m2[0][0]*m1[2][4]*m0[1][2]+m2[0][0]*m1[2][2]*m0[1][4]-m2[0][0]*m1[1][4]*m0[2][2]-m2[0][0]*m1[1][2]*m0[2][4]; M1(row,11) = m2[2][4]*m1[1][2]*m0[0][1]+m2[2][4]*m1[1][1]*m0[0][2]-m2[2][4]*m1[0][2]*m0[1][1]-m2[2][4]*m1[0][1]*m0[1][2]+m2[2][3]*m1[1][2]*m0[0][2]-m2[2][3]*m1[0][2]*m0[1][2]+m2[2][2]*m1[1][4]*m0[0][1]+m2[2][2]*m1[1][3]*m0[0][2]+m2[2][2]*m1[1][2]*m0[0][3]+m2[2][2]*m1[1][1]*m0[0][4]-m2[2][2]*m1[0][4]*m0[1][1]-m2[2][2]*m1[0][3]*m0[1][2]-m2[2][2]*m1[0][2]*m0[1][3]-m2[2][2]*m1[0][1]*m0[1][4]+m2[2][1]*m1[1][4]*m0[0][2]+m2[2][1]*m1[1][2]*m0[0][4]-m2[2][1]*m1[0][4]*m0[1][2]-m2[2][1]*m1[0][2]*m0[1][4]-m2[1][4]*m1[2][2]*m0[0][1]-m2[1][4]*m1[2][1]*m0[0][2]+m2[1][4]*m1[0][2]*m0[2][1]+m2[1][4]*m1[0][1]*m0[2][2]-m2[1][3]*m1[2][2]*m0[0][2]+m2[1][3]*m1[0][2]*m0[2][2]-m2[1][2]*m1[2][4]*m0[0][1]-m2[1][2]*m1[2][3]*m0[0][2]-m2[1][2]*m1[2][2]*m0[0][3]-m2[1][2]*m1[2][1]*m0[0][4]+m2[1][2]*m1[0][4]*m0[2][1]+m2[1][2]*m1[0][3]*m0[2][2]+m2[1][2]*m1[0][2]*m0[2][3]+m2[1][2]*m1[0][1]*m0[2][4]-m2[1][1]*m1[2][4]*m0[0][2]-m2[1][1]*m1[2][2]*m0[0][4]+m2[1][1]*m1[0][4]*m0[2][2]+m2[1][1]*m1[0][2]*m0[2][4]+m2[0][4]*m1[2][2]*m0[1][1]+m2[0][4]*m1[2][1]*m0[1][2]-m2[0][4]*m1[1][2]*m0[2][1]-m2[0][4]*m1[1][1]*m0[2][2]+m2[0][3]*m1[2][2]*m0[1][2]-m2[0][3]*m1[1][2]*m0[2][2]+m2[0][2]*m1[2][4]*m0[1][1]+m2[0][2]*m1[2][3]*m0[1][2]+m2[0][2]*m1[2][2]*m0[1][3]+m2[0][2]*m1[2][1]*m0[1][4]-m2[0][2]*m1[1][4]*m0[2][1]-m2[0][2]*m1[1][3]*m0[2][2]-m2[0][2]*m1[1][2]*m0[2][3]-m2[0][2]*m1[1][1]*m0[2][4]+m2[0][1]*m1[2][4]*m0[1][2]+m2[0][1]*m1[2][2]*m0[1][4]-m2[0][1]*m1[1][4]*m0[2][2]-m2[0][1]*m1[1][2]*m0[2][4]; M1(row,12) = m2[2][4]*m1[1][2]*m0[0][2]-m2[2][4]*m1[0][2]*m0[1][2]+m2[2][2]*m1[1][4]*m0[0][2]+m2[2][2]*m1[1][2]*m0[0][4]-m2[2][2]*m1[0][4]*m0[1][2]-m2[2][2]*m1[0][2]*m0[1][4]-m2[1][4]*m1[2][2]*m0[0][2]+m2[1][4]*m1[0][2]*m0[2][2]-m2[1][2]*m1[2][4]*m0[0][2]-m2[1][2]*m1[2][2]*m0[0][4]+m2[1][2]*m1[0][4]*m0[2][2]+m2[1][2]*m1[0][2]*m0[2][4]+m2[0][4]*m1[2][2]*m0[1][2]-m2[0][4]*m1[1][2]*m0[2][2]+m2[0][2]*m1[2][4]*m0[1][2]+m2[0][2]*m1[2][2]*m0[1][4]-m2[0][2]*m1[1][4]*m0[2][2]-m2[0][2]*m1[1][2]*m0[2][4]; M1(row,13) = m2[2][5]*m1[1][0]*m0[0][0]-m2[2][5]*m1[0][0]*m0[1][0]+m2[2][3]*m1[1][3]*m0[0][0]+m2[2][3]*m1[1][0]*m0[0][3]-m2[2][3]*m1[0][3]*m0[1][0]-m2[2][3]*m1[0][0]*m0[1][3]+m2[2][0]*m1[1][5]*m0[0][0]+m2[2][0]*m1[1][3]*m0[0][3]+m2[2][0]*m1[1][0]*m0[0][5]-m2[2][0]*m1[0][5]*m0[1][0]-m2[2][0]*m1[0][3]*m0[1][3]-m2[2][0]*m1[0][0]*m0[1][5]-m2[1][5]*m1[2][0]*m0[0][0]+m2[1][5]*m1[0][0]*m0[2][0]-m2[1][3]*m1[2][3]*m0[0][0]-m2[1][3]*m1[2][0]*m0[0][3]+m2[1][3]*m1[0][3]*m0[2][0]+m2[1][3]*m1[0][0]*m0[2][3]-m2[1][0]*m1[2][5]*m0[0][0]-m2[1][0]*m1[2][3]*m0[0][3]-m2[1][0]*m1[2][0]*m0[0][5]+m2[1][0]*m1[0][5]*m0[2][0]+m2[1][0]*m1[0][3]*m0[2][3]+m2[1][0]*m1[0][0]*m0[2][5]+m2[0][5]*m1[2][0]*m0[1][0]-m2[0][5]*m1[1][0]*m0[2][0]+m2[0][3]*m1[2][3]*m0[1][0]+m2[0][3]*m1[2][0]*m0[1][3]-m2[0][3]*m1[1][3]*m0[2][0]-m2[0][3]*m1[1][0]*m0[2][3]+m2[0][0]*m1[2][5]*m0[1][0]+m2[0][0]*m1[2][3]*m0[1][3]+m2[0][0]*m1[2][0]*m0[1][5]-m2[0][0]*m1[1][5]*m0[2][0]-m2[0][0]*m1[1][3]*m0[2][3]-m2[0][0]*m1[1][0]*m0[2][5]; M1(row,14) = m2[2][5]*m1[1][1]*m0[0][0]+m2[2][5]*m1[1][0]*m0[0][1]-m2[2][5]*m1[0][1]*m0[1][0]-m2[2][5]*m1[0][0]*m0[1][1]+m2[2][4]*m1[1][3]*m0[0][0]+m2[2][4]*m1[1][0]*m0[0][3]-m2[2][4]*m1[0][3]*m0[1][0]-m2[2][4]*m1[0][0]*m0[1][3]+m2[2][3]*m1[1][4]*m0[0][0]+m2[2][3]*m1[1][3]*m0[0][1]+m2[2][3]*m1[1][1]*m0[0][3]+m2[2][3]*m1[1][0]*m0[0][4]-m2[2][3]*m1[0][4]*m0[1][0]-m2[2][3]*m1[0][3]*m0[1][1]-m2[2][3]*m1[0][1]*m0[1][3]-m2[2][3]*m1[0][0]*m0[1][4]+m2[2][1]*m1[1][5]*m0[0][0]+m2[2][1]*m1[1][3]*m0[0][3]+m2[2][1]*m1[1][0]*m0[0][5]-m2[2][1]*m1[0][5]*m0[1][0]-m2[2][1]*m1[0][3]*m0[1][3]-m2[2][1]*m1[0][0]*m0[1][5]+m2[2][0]*m1[1][5]*m0[0][1]+m2[2][0]*m1[1][4]*m0[0][3]+m2[2][0]*m1[1][3]*m0[0][4]+m2[2][0]*m1[1][1]*m0[0][5]-m2[2][0]*m1[0][5]*m0[1][1]-m2[2][0]*m1[0][4]*m0[1][3]-m2[2][0]*m1[0][3]*m0[1][4]-m2[2][0]*m1[0][1]*m0[1][5]-m2[1][5]*m1[2][1]*m0[0][0]-m2[1][5]*m1[2][0]*m0[0][1]+m2[1][5]*m1[0][1]*m0[2][0]+m2[1][5]*m1[0][0]*m0[2][1]-m2[1][4]*m1[2][3]*m0[0][0]-m2[1][4]*m1[2][0]*m0[0][3]+m2[1][4]*m1[0][3]*m0[2][0]+m2[1][4]*m1[0][0]*m0[2][3]-m2[1][3]*m1[2][4]*m0[0][0]-m2[1][3]*m1[2][3]*m0[0][1]-m2[1][3]*m1[2][1]*m0[0][3]-m2[1][3]*m1[2][0]*m0[0][4]+m2[1][3]*m1[0][4]*m0[2][0]+m2[1][3]*m1[0][3]*m0[2][1]+m2[1][3]*m1[0][1]*m0[2][3]+m2[1][3]*m1[0][0]*m0[2][4]-m2[1][1]*m1[2][5]*m0[0][0]-m2[1][1]*m1[2][3]*m0[0][3]-m2[1][1]*m1[2][0]*m0[0][5]+m2[1][1]*m1[0][5]*m0[2][0]+m2[1][1]*m1[0][3]*m0[2][3]+m2[1][1]*m1[0][0]*m0[2][5]-m2[1][0]*m1[2][5]*m0[0][1]-m2[1][0]*m1[2][4]*m0[0][3]-m2[1][0]*m1[2][3]*m0[0][4]-m2[1][0]*m1[2][1]*m0[0][5]+m2[1][0]*m1[0][5]*m0[2][1]+m2[1][0]*m1[0][4]*m0[2][3]+m2[1][0]*m1[0][3]*m0[2][4]+m2[1][0]*m1[0][1]*m0[2][5]+m2[0][5]*m1[2][1]*m0[1][0]+m2[0][5]*m1[2][0]*m0[1][1]-m2[0][5]*m1[1][1]*m0[2][0]-m2[0][5]*m1[1][0]*m0[2][1]+m2[0][4]*m1[2][3]*m0[1][0]+m2[0][4]*m1[2][0]*m0[1][3]-m2[0][4]*m1[1][3]*m0[2][0]-m2[0][4]*m1[1][0]*m0[2][3]+m2[0][3]*m1[2][4]*m0[1][0]+m2[0][3]*m1[2][3]*m0[1][1]+m2[0][3]*m1[2][1]*m0[1][3]+m2[0][3]*m1[2][0]*m0[1][4]-m2[0][3]*m1[1][4]*m0[2][0]-m2[0][3]*m1[1][3]*m0[2][1]-m2[0][3]*m1[1][1]*m0[2][3]-m2[0][3]*m1[1][0]*m0[2][4]+m2[0][1]*m1[2][5]*m0[1][0]+m2[0][1]*m1[2][3]*m0[1][3]+m2[0][1]*m1[2][0]*m0[1][5]-m2[0][1]*m1[1][5]*m0[2][0]-m2[0][1]*m1[1][3]*m0[2][3]-m2[0][1]*m1[1][0]*m0[2][5]+m2[0][0]*m1[2][5]*m0[1][1]+m2[0][0]*m1[2][4]*m0[1][3]+m2[0][0]*m1[2][3]*m0[1][4]+m2[0][0]*m1[2][1]*m0[1][5]-m2[0][0]*m1[1][5]*m0[2][1]-m2[0][0]*m1[1][4]*m0[2][3]-m2[0][0]*m1[1][3]*m0[2][4]-m2[0][0]*m1[1][1]*m0[2][5]; M1(row,15) = m2[2][5]*m1[1][2]*m0[0][0]+m2[2][5]*m1[1][1]*m0[0][1]+m2[2][5]*m1[1][0]*m0[0][2]-m2[2][5]*m1[0][2]*m0[1][0]-m2[2][5]*m1[0][1]*m0[1][1]-m2[2][5]*m1[0][0]*m0[1][2]+m2[2][4]*m1[1][4]*m0[0][0]+m2[2][4]*m1[1][3]*m0[0][1]+m2[2][4]*m1[1][1]*m0[0][3]+m2[2][4]*m1[1][0]*m0[0][4]-m2[2][4]*m1[0][4]*m0[1][0]-m2[2][4]*m1[0][3]*m0[1][1]-m2[2][4]*m1[0][1]*m0[1][3]-m2[2][4]*m1[0][0]*m0[1][4]+m2[2][3]*m1[1][4]*m0[0][1]+m2[2][3]*m1[1][3]*m0[0][2]+m2[2][3]*m1[1][2]*m0[0][3]+m2[2][3]*m1[1][1]*m0[0][4]-m2[2][3]*m1[0][4]*m0[1][1]-m2[2][3]*m1[0][3]*m0[1][2]-m2[2][3]*m1[0][2]*m0[1][3]-m2[2][3]*m1[0][1]*m0[1][4]+m2[2][2]*m1[1][5]*m0[0][0]+m2[2][2]*m1[1][3]*m0[0][3]+m2[2][2]*m1[1][0]*m0[0][5]-m2[2][2]*m1[0][5]*m0[1][0]-m2[2][2]*m1[0][3]*m0[1][3]-m2[2][2]*m1[0][0]*m0[1][5]+m2[2][1]*m1[1][5]*m0[0][1]+m2[2][1]*m1[1][4]*m0[0][3]+m2[2][1]*m1[1][3]*m0[0][4]+m2[2][1]*m1[1][1]*m0[0][5]-m2[2][1]*m1[0][5]*m0[1][1]-m2[2][1]*m1[0][4]*m0[1][3]-m2[2][1]*m1[0][3]*m0[1][4]-m2[2][1]*m1[0][1]*m0[1][5]+m2[2][0]*m1[1][5]*m0[0][2]+m2[2][0]*m1[1][4]*m0[0][4]+m2[2][0]*m1[1][2]*m0[0][5]-m2[2][0]*m1[0][5]*m0[1][2]-m2[2][0]*m1[0][4]*m0[1][4]-m2[2][0]*m1[0][2]*m0[1][5]-m2[1][5]*m1[2][2]*m0[0][0]-m2[1][5]*m1[2][1]*m0[0][1]-m2[1][5]*m1[2][0]*m0[0][2]+m2[1][5]*m1[0][2]*m0[2][0]+m2[1][5]*m1[0][1]*m0[2][1]+m2[1][5]*m1[0][0]*m0[2][2]-m2[1][4]*m1[2][4]*m0[0][0]-m2[1][4]*m1[2][3]*m0[0][1]-m2[1][4]*m1[2][1]*m0[0][3]-m2[1][4]*m1[2][0]*m0[0][4]+m2[1][4]*m1[0][4]*m0[2][0]+m2[1][4]*m1[0][3]*m0[2][1]+m2[1][4]*m1[0][1]*m0[2][3]+m2[1][4]*m1[0][0]*m0[2][4]-m2[1][3]*m1[2][4]*m0[0][1]-m2[1][3]*m1[2][3]*m0[0][2]-m2[1][3]*m1[2][2]*m0[0][3]-m2[1][3]*m1[2][1]*m0[0][4]+m2[1][3]*m1[0][4]*m0[2][1]+m2[1][3]*m1[0][3]*m0[2][2]+m2[1][3]*m1[0][2]*m0[2][3]+m2[1][3]*m1[0][1]*m0[2][4]-m2[1][2]*m1[2][5]*m0[0][0]-m2[1][2]*m1[2][3]*m0[0][3]-m2[1][2]*m1[2][0]*m0[0][5]+m2[1][2]*m1[0][5]*m0[2][0]+m2[1][2]*m1[0][3]*m0[2][3]+m2[1][2]*m1[0][0]*m0[2][5]-m2[1][1]*m1[2][5]*m0[0][1]-m2[1][1]*m1[2][4]*m0[0][3]-m2[1][1]*m1[2][3]*m0[0][4]-m2[1][1]*m1[2][1]*m0[0][5]+m2[1][1]*m1[0][5]*m0[2][1]+m2[1][1]*m1[0][4]*m0[2][3]+m2[1][1]*m1[0][3]*m0[2][4]+m2[1][1]*m1[0][1]*m0[2][5]-m2[1][0]*m1[2][5]*m0[0][2]-m2[1][0]*m1[2][4]*m0[0][4]-m2[1][0]*m1[2][2]*m0[0][5]+m2[1][0]*m1[0][5]*m0[2][2]+m2[1][0]*m1[0][4]*m0[2][4]+m2[1][0]*m1[0][2]*m0[2][5]+m2[0][5]*m1[2][2]*m0[1][0]+m2[0][5]*m1[2][1]*m0[1][1]+m2[0][5]*m1[2][0]*m0[1][2]-m2[0][5]*m1[1][2]*m0[2][0]-m2[0][5]*m1[1][1]*m0[2][1]-m2[0][5]*m1[1][0]*m0[2][2]+m2[0][4]*m1[2][4]*m0[1][0]+m2[0][4]*m1[2][3]*m0[1][1]+m2[0][4]*m1[2][1]*m0[1][3]+m2[0][4]*m1[2][0]*m0[1][4]-m2[0][4]*m1[1][4]*m0[2][0]-m2[0][4]*m1[1][3]*m0[2][1]-m2[0][4]*m1[1][1]*m0[2][3]-m2[0][4]*m1[1][0]*m0[2][4]+m2[0][3]*m1[2][4]*m0[1][1]+m2[0][3]*m1[2][3]*m0[1][2]+m2[0][3]*m1[2][2]*m0[1][3]+m2[0][3]*m1[2][1]*m0[1][4]-m2[0][3]*m1[1][4]*m0[2][1]-m2[0][3]*m1[1][3]*m0[2][2]-m2[0][3]*m1[1][2]*m0[2][3]-m2[0][3]*m1[1][1]*m0[2][4]+m2[0][2]*m1[2][5]*m0[1][0]+m2[0][2]*m1[2][3]*m0[1][3]+m2[0][2]*m1[2][0]*m0[1][5]-m2[0][2]*m1[1][5]*m0[2][0]-m2[0][2]*m1[1][3]*m0[2][3]-m2[0][2]*m1[1][0]*m0[2][5]+m2[0][1]*m1[2][5]*m0[1][1]+m2[0][1]*m1[2][4]*m0[1][3]+m2[0][1]*m1[2][3]*m0[1][4]+m2[0][1]*m1[2][1]*m0[1][5]-m2[0][1]*m1[1][5]*m0[2][1]-m2[0][1]*m1[1][4]*m0[2][3]-m2[0][1]*m1[1][3]*m0[2][4]-m2[0][1]*m1[1][1]*m0[2][5]+m2[0][0]*m1[2][5]*m0[1][2]+m2[0][0]*m1[2][4]*m0[1][4]+m2[0][0]*m1[2][2]*m0[1][5]-m2[0][0]*m1[1][5]*m0[2][2]-m2[0][0]*m1[1][4]*m0[2][4]-m2[0][0]*m1[1][2]*m0[2][5]; M1(row,16) = m2[2][5]*m1[1][2]*m0[0][1]+m2[2][5]*m1[1][1]*m0[0][2]-m2[2][5]*m1[0][2]*m0[1][1]-m2[2][5]*m1[0][1]*m0[1][2]+m2[2][4]*m1[1][4]*m0[0][1]+m2[2][4]*m1[1][3]*m0[0][2]+m2[2][4]*m1[1][2]*m0[0][3]+m2[2][4]*m1[1][1]*m0[0][4]-m2[2][4]*m1[0][4]*m0[1][1]-m2[2][4]*m1[0][3]*m0[1][2]-m2[2][4]*m1[0][2]*m0[1][3]-m2[2][4]*m1[0][1]*m0[1][4]+m2[2][3]*m1[1][4]*m0[0][2]+m2[2][3]*m1[1][2]*m0[0][4]-m2[2][3]*m1[0][4]*m0[1][2]-m2[2][3]*m1[0][2]*m0[1][4]+m2[2][2]*m1[1][5]*m0[0][1]+m2[2][2]*m1[1][4]*m0[0][3]+m2[2][2]*m1[1][3]*m0[0][4]+m2[2][2]*m1[1][1]*m0[0][5]-m2[2][2]*m1[0][5]*m0[1][1]-m2[2][2]*m1[0][4]*m0[1][3]-m2[2][2]*m1[0][3]*m0[1][4]-m2[2][2]*m1[0][1]*m0[1][5]+m2[2][1]*m1[1][5]*m0[0][2]+m2[2][1]*m1[1][4]*m0[0][4]+m2[2][1]*m1[1][2]*m0[0][5]-m2[2][1]*m1[0][5]*m0[1][2]-m2[2][1]*m1[0][4]*m0[1][4]-m2[2][1]*m1[0][2]*m0[1][5]-m2[1][5]*m1[2][2]*m0[0][1]-m2[1][5]*m1[2][1]*m0[0][2]+m2[1][5]*m1[0][2]*m0[2][1]+m2[1][5]*m1[0][1]*m0[2][2]-m2[1][4]*m1[2][4]*m0[0][1]-m2[1][4]*m1[2][3]*m0[0][2]-m2[1][4]*m1[2][2]*m0[0][3]-m2[1][4]*m1[2][1]*m0[0][4]+m2[1][4]*m1[0][4]*m0[2][1]+m2[1][4]*m1[0][3]*m0[2][2]+m2[1][4]*m1[0][2]*m0[2][3]+m2[1][4]*m1[0][1]*m0[2][4]-m2[1][3]*m1[2][4]*m0[0][2]-m2[1][3]*m1[2][2]*m0[0][4]+m2[1][3]*m1[0][4]*m0[2][2]+m2[1][3]*m1[0][2]*m0[2][4]-m2[1][2]*m1[2][5]*m0[0][1]-m2[1][2]*m1[2][4]*m0[0][3]-m2[1][2]*m1[2][3]*m0[0][4]-m2[1][2]*m1[2][1]*m0[0][5]+m2[1][2]*m1[0][5]*m0[2][1]+m2[1][2]*m1[0][4]*m0[2][3]+m2[1][2]*m1[0][3]*m0[2][4]+m2[1][2]*m1[0][1]*m0[2][5]-m2[1][1]*m1[2][5]*m0[0][2]-m2[1][1]*m1[2][4]*m0[0][4]-m2[1][1]*m1[2][2]*m0[0][5]+m2[1][1]*m1[0][5]*m0[2][2]+m2[1][1]*m1[0][4]*m0[2][4]+m2[1][1]*m1[0][2]*m0[2][5]+m2[0][5]*m1[2][2]*m0[1][1]+m2[0][5]*m1[2][1]*m0[1][2]-m2[0][5]*m1[1][2]*m0[2][1]-m2[0][5]*m1[1][1]*m0[2][2]+m2[0][4]*m1[2][4]*m0[1][1]+m2[0][4]*m1[2][3]*m0[1][2]+m2[0][4]*m1[2][2]*m0[1][3]+m2[0][4]*m1[2][1]*m0[1][4]-m2[0][4]*m1[1][4]*m0[2][1]-m2[0][4]*m1[1][3]*m0[2][2]-m2[0][4]*m1[1][2]*m0[2][3]-m2[0][4]*m1[1][1]*m0[2][4]+m2[0][3]*m1[2][4]*m0[1][2]+m2[0][3]*m1[2][2]*m0[1][4]-m2[0][3]*m1[1][4]*m0[2][2]-m2[0][3]*m1[1][2]*m0[2][4]+m2[0][2]*m1[2][5]*m0[1][1]+m2[0][2]*m1[2][4]*m0[1][3]+m2[0][2]*m1[2][3]*m0[1][4]+m2[0][2]*m1[2][1]*m0[1][5]-m2[0][2]*m1[1][5]*m0[2][1]-m2[0][2]*m1[1][4]*m0[2][3]-m2[0][2]*m1[1][3]*m0[2][4]-m2[0][2]*m1[1][1]*m0[2][5]+m2[0][1]*m1[2][5]*m0[1][2]+m2[0][1]*m1[2][4]*m0[1][4]+m2[0][1]*m1[2][2]*m0[1][5]-m2[0][1]*m1[1][5]*m0[2][2]-m2[0][1]*m1[1][4]*m0[2][4]-m2[0][1]*m1[1][2]*m0[2][5]; M1(row,17) = m2[2][5]*m1[1][2]*m0[0][2]-m2[2][5]*m1[0][2]*m0[1][2]+m2[2][4]*m1[1][4]*m0[0][2]+m2[2][4]*m1[1][2]*m0[0][4]-m2[2][4]*m1[0][4]*m0[1][2]-m2[2][4]*m1[0][2]*m0[1][4]+m2[2][2]*m1[1][5]*m0[0][2]+m2[2][2]*m1[1][4]*m0[0][4]+m2[2][2]*m1[1][2]*m0[0][5]-m2[2][2]*m1[0][5]*m0[1][2]-m2[2][2]*m1[0][4]*m0[1][4]-m2[2][2]*m1[0][2]*m0[1][5]-m2[1][5]*m1[2][2]*m0[0][2]+m2[1][5]*m1[0][2]*m0[2][2]-m2[1][4]*m1[2][4]*m0[0][2]-m2[1][4]*m1[2][2]*m0[0][4]+m2[1][4]*m1[0][4]*m0[2][2]+m2[1][4]*m1[0][2]*m0[2][4]-m2[1][2]*m1[2][5]*m0[0][2]-m2[1][2]*m1[2][4]*m0[0][4]-m2[1][2]*m1[2][2]*m0[0][5]+m2[1][2]*m1[0][5]*m0[2][2]+m2[1][2]*m1[0][4]*m0[2][4]+m2[1][2]*m1[0][2]*m0[2][5]+m2[0][5]*m1[2][2]*m0[1][2]-m2[0][5]*m1[1][2]*m0[2][2]+m2[0][4]*m1[2][4]*m0[1][2]+m2[0][4]*m1[2][2]*m0[1][4]-m2[0][4]*m1[1][4]*m0[2][2]-m2[0][4]*m1[1][2]*m0[2][4]+m2[0][2]*m1[2][5]*m0[1][2]+m2[0][2]*m1[2][4]*m0[1][4]+m2[0][2]*m1[2][2]*m0[1][5]-m2[0][2]*m1[1][5]*m0[2][2]-m2[0][2]*m1[1][4]*m0[2][4]-m2[0][2]*m1[1][2]*m0[2][5]; M1(row,18) = m2[2][5]*m1[1][3]*m0[0][0]+m2[2][5]*m1[1][0]*m0[0][3]-m2[2][5]*m1[0][3]*m0[1][0]-m2[2][5]*m1[0][0]*m0[1][3]+m2[2][3]*m1[1][5]*m0[0][0]+m2[2][3]*m1[1][3]*m0[0][3]+m2[2][3]*m1[1][0]*m0[0][5]-m2[2][3]*m1[0][5]*m0[1][0]-m2[2][3]*m1[0][3]*m0[1][3]-m2[2][3]*m1[0][0]*m0[1][5]+m2[2][0]*m1[1][5]*m0[0][3]+m2[2][0]*m1[1][3]*m0[0][5]-m2[2][0]*m1[0][5]*m0[1][3]-m2[2][0]*m1[0][3]*m0[1][5]-m2[1][5]*m1[2][3]*m0[0][0]-m2[1][5]*m1[2][0]*m0[0][3]+m2[1][5]*m1[0][3]*m0[2][0]+m2[1][5]*m1[0][0]*m0[2][3]-m2[1][3]*m1[2][5]*m0[0][0]-m2[1][3]*m1[2][3]*m0[0][3]-m2[1][3]*m1[2][0]*m0[0][5]+m2[1][3]*m1[0][5]*m0[2][0]+m2[1][3]*m1[0][3]*m0[2][3]+m2[1][3]*m1[0][0]*m0[2][5]-m2[1][0]*m1[2][5]*m0[0][3]-m2[1][0]*m1[2][3]*m0[0][5]+m2[1][0]*m1[0][5]*m0[2][3]+m2[1][0]*m1[0][3]*m0[2][5]+m2[0][5]*m1[2][3]*m0[1][0]+m2[0][5]*m1[2][0]*m0[1][3]-m2[0][5]*m1[1][3]*m0[2][0]-m2[0][5]*m1[1][0]*m0[2][3]+m2[0][3]*m1[2][5]*m0[1][0]+m2[0][3]*m1[2][3]*m0[1][3]+m2[0][3]*m1[2][0]*m0[1][5]-m2[0][3]*m1[1][5]*m0[2][0]-m2[0][3]*m1[1][3]*m0[2][3]-m2[0][3]*m1[1][0]*m0[2][5]+m2[0][0]*m1[2][5]*m0[1][3]+m2[0][0]*m1[2][3]*m0[1][5]-m2[0][0]*m1[1][5]*m0[2][3]-m2[0][0]*m1[1][3]*m0[2][5]; M1(row,19) = m2[2][5]*m1[1][4]*m0[0][0]+m2[2][5]*m1[1][3]*m0[0][1]+m2[2][5]*m1[1][1]*m0[0][3]+m2[2][5]*m1[1][0]*m0[0][4]-m2[2][5]*m1[0][4]*m0[1][0]-m2[2][5]*m1[0][3]*m0[1][1]-m2[2][5]*m1[0][1]*m0[1][3]-m2[2][5]*m1[0][0]*m0[1][4]+m2[2][4]*m1[1][5]*m0[0][0]+m2[2][4]*m1[1][3]*m0[0][3]+m2[2][4]*m1[1][0]*m0[0][5]-m2[2][4]*m1[0][5]*m0[1][0]-m2[2][4]*m1[0][3]*m0[1][3]-m2[2][4]*m1[0][0]*m0[1][5]+m2[2][3]*m1[1][5]*m0[0][1]+m2[2][3]*m1[1][4]*m0[0][3]+m2[2][3]*m1[1][3]*m0[0][4]+m2[2][3]*m1[1][1]*m0[0][5]-m2[2][3]*m1[0][5]*m0[1][1]-m2[2][3]*m1[0][4]*m0[1][3]-m2[2][3]*m1[0][3]*m0[1][4]-m2[2][3]*m1[0][1]*m0[1][5]+m2[2][1]*m1[1][5]*m0[0][3]+m2[2][1]*m1[1][3]*m0[0][5]-m2[2][1]*m1[0][5]*m0[1][3]-m2[2][1]*m1[0][3]*m0[1][5]+m2[2][0]*m1[1][5]*m0[0][4]+m2[2][0]*m1[1][4]*m0[0][5]-m2[2][0]*m1[0][5]*m0[1][4]-m2[2][0]*m1[0][4]*m0[1][5]-m2[1][5]*m1[2][4]*m0[0][0]-m2[1][5]*m1[2][3]*m0[0][1]-m2[1][5]*m1[2][1]*m0[0][3]-m2[1][5]*m1[2][0]*m0[0][4]+m2[1][5]*m1[0][4]*m0[2][0]+m2[1][5]*m1[0][3]*m0[2][1]+m2[1][5]*m1[0][1]*m0[2][3]+m2[1][5]*m1[0][0]*m0[2][4]-m2[1][4]*m1[2][5]*m0[0][0]-m2[1][4]*m1[2][3]*m0[0][3]-m2[1][4]*m1[2][0]*m0[0][5]+m2[1][4]*m1[0][5]*m0[2][0]+m2[1][4]*m1[0][3]*m0[2][3]+m2[1][4]*m1[0][0]*m0[2][5]-m2[1][3]*m1[2][5]*m0[0][1]-m2[1][3]*m1[2][4]*m0[0][3]-m2[1][3]*m1[2][3]*m0[0][4]-m2[1][3]*m1[2][1]*m0[0][5]+m2[1][3]*m1[0][5]*m0[2][1]+m2[1][3]*m1[0][4]*m0[2][3]+m2[1][3]*m1[0][3]*m0[2][4]+m2[1][3]*m1[0][1]*m0[2][5]-m2[1][1]*m1[2][5]*m0[0][3]-m2[1][1]*m1[2][3]*m0[0][5]+m2[1][1]*m1[0][5]*m0[2][3]+m2[1][1]*m1[0][3]*m0[2][5]-m2[1][0]*m1[2][5]*m0[0][4]-m2[1][0]*m1[2][4]*m0[0][5]+m2[1][0]*m1[0][5]*m0[2][4]+m2[1][0]*m1[0][4]*m0[2][5]+m2[0][5]*m1[2][4]*m0[1][0]+m2[0][5]*m1[2][3]*m0[1][1]+m2[0][5]*m1[2][1]*m0[1][3]+m2[0][5]*m1[2][0]*m0[1][4]-m2[0][5]*m1[1][4]*m0[2][0]-m2[0][5]*m1[1][3]*m0[2][1]-m2[0][5]*m1[1][1]*m0[2][3]-m2[0][5]*m1[1][0]*m0[2][4]+m2[0][4]*m1[2][5]*m0[1][0]+m2[0][4]*m1[2][3]*m0[1][3]+m2[0][4]*m1[2][0]*m0[1][5]-m2[0][4]*m1[1][5]*m0[2][0]-m2[0][4]*m1[1][3]*m0[2][3]-m2[0][4]*m1[1][0]*m0[2][5]+m2[0][3]*m1[2][5]*m0[1][1]+m2[0][3]*m1[2][4]*m0[1][3]+m2[0][3]*m1[2][3]*m0[1][4]+m2[0][3]*m1[2][1]*m0[1][5]-m2[0][3]*m1[1][5]*m0[2][1]-m2[0][3]*m1[1][4]*m0[2][3]-m2[0][3]*m1[1][3]*m0[2][4]-m2[0][3]*m1[1][1]*m0[2][5]+m2[0][1]*m1[2][5]*m0[1][3]+m2[0][1]*m1[2][3]*m0[1][5]-m2[0][1]*m1[1][5]*m0[2][3]-m2[0][1]*m1[1][3]*m0[2][5]+m2[0][0]*m1[2][5]*m0[1][4]+m2[0][0]*m1[2][4]*m0[1][5]-m2[0][0]*m1[1][5]*m0[2][4]-m2[0][0]*m1[1][4]*m0[2][5]; M1(row,20) = m2[2][5]*m1[1][4]*m0[0][1]+m2[2][5]*m1[1][3]*m0[0][2]+m2[2][5]*m1[1][2]*m0[0][3]+m2[2][5]*m1[1][1]*m0[0][4]-m2[2][5]*m1[0][4]*m0[1][1]-m2[2][5]*m1[0][3]*m0[1][2]-m2[2][5]*m1[0][2]*m0[1][3]-m2[2][5]*m1[0][1]*m0[1][4]+m2[2][4]*m1[1][5]*m0[0][1]+m2[2][4]*m1[1][4]*m0[0][3]+m2[2][4]*m1[1][3]*m0[0][4]+m2[2][4]*m1[1][1]*m0[0][5]-m2[2][4]*m1[0][5]*m0[1][1]-m2[2][4]*m1[0][4]*m0[1][3]-m2[2][4]*m1[0][3]*m0[1][4]-m2[2][4]*m1[0][1]*m0[1][5]+m2[2][3]*m1[1][5]*m0[0][2]+m2[2][3]*m1[1][4]*m0[0][4]+m2[2][3]*m1[1][2]*m0[0][5]-m2[2][3]*m1[0][5]*m0[1][2]-m2[2][3]*m1[0][4]*m0[1][4]-m2[2][3]*m1[0][2]*m0[1][5]+m2[2][2]*m1[1][5]*m0[0][3]+m2[2][2]*m1[1][3]*m0[0][5]-m2[2][2]*m1[0][5]*m0[1][3]-m2[2][2]*m1[0][3]*m0[1][5]+m2[2][1]*m1[1][5]*m0[0][4]+m2[2][1]*m1[1][4]*m0[0][5]-m2[2][1]*m1[0][5]*m0[1][4]-m2[2][1]*m1[0][4]*m0[1][5]-m2[1][5]*m1[2][4]*m0[0][1]-m2[1][5]*m1[2][3]*m0[0][2]-m2[1][5]*m1[2][2]*m0[0][3]-m2[1][5]*m1[2][1]*m0[0][4]+m2[1][5]*m1[0][4]*m0[2][1]+m2[1][5]*m1[0][3]*m0[2][2]+m2[1][5]*m1[0][2]*m0[2][3]+m2[1][5]*m1[0][1]*m0[2][4]-m2[1][4]*m1[2][5]*m0[0][1]-m2[1][4]*m1[2][4]*m0[0][3]-m2[1][4]*m1[2][3]*m0[0][4]-m2[1][4]*m1[2][1]*m0[0][5]+m2[1][4]*m1[0][5]*m0[2][1]+m2[1][4]*m1[0][4]*m0[2][3]+m2[1][4]*m1[0][3]*m0[2][4]+m2[1][4]*m1[0][1]*m0[2][5]-m2[1][3]*m1[2][5]*m0[0][2]-m2[1][3]*m1[2][4]*m0[0][4]-m2[1][3]*m1[2][2]*m0[0][5]+m2[1][3]*m1[0][5]*m0[2][2]+m2[1][3]*m1[0][4]*m0[2][4]+m2[1][3]*m1[0][2]*m0[2][5]-m2[1][2]*m1[2][5]*m0[0][3]-m2[1][2]*m1[2][3]*m0[0][5]+m2[1][2]*m1[0][5]*m0[2][3]+m2[1][2]*m1[0][3]*m0[2][5]-m2[1][1]*m1[2][5]*m0[0][4]-m2[1][1]*m1[2][4]*m0[0][5]+m2[1][1]*m1[0][5]*m0[2][4]+m2[1][1]*m1[0][4]*m0[2][5]+m2[0][5]*m1[2][4]*m0[1][1]+m2[0][5]*m1[2][3]*m0[1][2]+m2[0][5]*m1[2][2]*m0[1][3]+m2[0][5]*m1[2][1]*m0[1][4]-m2[0][5]*m1[1][4]*m0[2][1]-m2[0][5]*m1[1][3]*m0[2][2]-m2[0][5]*m1[1][2]*m0[2][3]-m2[0][5]*m1[1][1]*m0[2][4]+m2[0][4]*m1[2][5]*m0[1][1]+m2[0][4]*m1[2][4]*m0[1][3]+m2[0][4]*m1[2][3]*m0[1][4]+m2[0][4]*m1[2][1]*m0[1][5]-m2[0][4]*m1[1][5]*m0[2][1]-m2[0][4]*m1[1][4]*m0[2][3]-m2[0][4]*m1[1][3]*m0[2][4]-m2[0][4]*m1[1][1]*m0[2][5]+m2[0][3]*m1[2][5]*m0[1][2]+m2[0][3]*m1[2][4]*m0[1][4]+m2[0][3]*m1[2][2]*m0[1][5]-m2[0][3]*m1[1][5]*m0[2][2]-m2[0][3]*m1[1][4]*m0[2][4]-m2[0][3]*m1[1][2]*m0[2][5]+m2[0][2]*m1[2][5]*m0[1][3]+m2[0][2]*m1[2][3]*m0[1][5]-m2[0][2]*m1[1][5]*m0[2][3]-m2[0][2]*m1[1][3]*m0[2][5]+m2[0][1]*m1[2][5]*m0[1][4]+m2[0][1]*m1[2][4]*m0[1][5]-m2[0][1]*m1[1][5]*m0[2][4]-m2[0][1]*m1[1][4]*m0[2][5]; M1(row,21) = m2[2][5]*m1[1][4]*m0[0][2]+m2[2][5]*m1[1][2]*m0[0][4]-m2[2][5]*m1[0][4]*m0[1][2]-m2[2][5]*m1[0][2]*m0[1][4]+m2[2][4]*m1[1][5]*m0[0][2]+m2[2][4]*m1[1][4]*m0[0][4]+m2[2][4]*m1[1][2]*m0[0][5]-m2[2][4]*m1[0][5]*m0[1][2]-m2[2][4]*m1[0][4]*m0[1][4]-m2[2][4]*m1[0][2]*m0[1][5]+m2[2][2]*m1[1][5]*m0[0][4]+m2[2][2]*m1[1][4]*m0[0][5]-m2[2][2]*m1[0][5]*m0[1][4]-m2[2][2]*m1[0][4]*m0[1][5]-m2[1][5]*m1[2][4]*m0[0][2]-m2[1][5]*m1[2][2]*m0[0][4]+m2[1][5]*m1[0][4]*m0[2][2]+m2[1][5]*m1[0][2]*m0[2][4]-m2[1][4]*m1[2][5]*m0[0][2]-m2[1][4]*m1[2][4]*m0[0][4]-m2[1][4]*m1[2][2]*m0[0][5]+m2[1][4]*m1[0][5]*m0[2][2]+m2[1][4]*m1[0][4]*m0[2][4]+m2[1][4]*m1[0][2]*m0[2][5]-m2[1][2]*m1[2][5]*m0[0][4]-m2[1][2]*m1[2][4]*m0[0][5]+m2[1][2]*m1[0][5]*m0[2][4]+m2[1][2]*m1[0][4]*m0[2][5]+m2[0][5]*m1[2][4]*m0[1][2]+m2[0][5]*m1[2][2]*m0[1][4]-m2[0][5]*m1[1][4]*m0[2][2]-m2[0][5]*m1[1][2]*m0[2][4]+m2[0][4]*m1[2][5]*m0[1][2]+m2[0][4]*m1[2][4]*m0[1][4]+m2[0][4]*m1[2][2]*m0[1][5]-m2[0][4]*m1[1][5]*m0[2][2]-m2[0][4]*m1[1][4]*m0[2][4]-m2[0][4]*m1[1][2]*m0[2][5]+m2[0][2]*m1[2][5]*m0[1][4]+m2[0][2]*m1[2][4]*m0[1][5]-m2[0][2]*m1[1][5]*m0[2][4]-m2[0][2]*m1[1][4]*m0[2][5]; M1(row,22) = m2[2][5]*m1[1][5]*m0[0][0]+m2[2][5]*m1[1][3]*m0[0][3]+m2[2][5]*m1[1][0]*m0[0][5]-m2[2][5]*m1[0][5]*m0[1][0]-m2[2][5]*m1[0][3]*m0[1][3]-m2[2][5]*m1[0][0]*m0[1][5]+m2[2][3]*m1[1][5]*m0[0][3]+m2[2][3]*m1[1][3]*m0[0][5]-m2[2][3]*m1[0][5]*m0[1][3]-m2[2][3]*m1[0][3]*m0[1][5]+m2[2][0]*m1[1][5]*m0[0][5]-m2[2][0]*m1[0][5]*m0[1][5]-m2[1][5]*m1[2][5]*m0[0][0]-m2[1][5]*m1[2][3]*m0[0][3]-m2[1][5]*m1[2][0]*m0[0][5]+m2[1][5]*m1[0][5]*m0[2][0]+m2[1][5]*m1[0][3]*m0[2][3]+m2[1][5]*m1[0][0]*m0[2][5]-m2[1][3]*m1[2][5]*m0[0][3]-m2[1][3]*m1[2][3]*m0[0][5]+m2[1][3]*m1[0][5]*m0[2][3]+m2[1][3]*m1[0][3]*m0[2][5]-m2[1][0]*m1[2][5]*m0[0][5]+m2[1][0]*m1[0][5]*m0[2][5]+m2[0][5]*m1[2][5]*m0[1][0]+m2[0][5]*m1[2][3]*m0[1][3]+m2[0][5]*m1[2][0]*m0[1][5]-m2[0][5]*m1[1][5]*m0[2][0]-m2[0][5]*m1[1][3]*m0[2][3]-m2[0][5]*m1[1][0]*m0[2][5]+m2[0][3]*m1[2][5]*m0[1][3]+m2[0][3]*m1[2][3]*m0[1][5]-m2[0][3]*m1[1][5]*m0[2][3]-m2[0][3]*m1[1][3]*m0[2][5]+m2[0][0]*m1[2][5]*m0[1][5]-m2[0][0]*m1[1][5]*m0[2][5]; M1(row,23) = m2[2][5]*m1[1][5]*m0[0][1]+m2[2][5]*m1[1][4]*m0[0][3]+m2[2][5]*m1[1][3]*m0[0][4]+m2[2][5]*m1[1][1]*m0[0][5]-m2[2][5]*m1[0][5]*m0[1][1]-m2[2][5]*m1[0][4]*m0[1][3]-m2[2][5]*m1[0][3]*m0[1][4]-m2[2][5]*m1[0][1]*m0[1][5]+m2[2][4]*m1[1][5]*m0[0][3]+m2[2][4]*m1[1][3]*m0[0][5]-m2[2][4]*m1[0][5]*m0[1][3]-m2[2][4]*m1[0][3]*m0[1][5]+m2[2][3]*m1[1][5]*m0[0][4]+m2[2][3]*m1[1][4]*m0[0][5]-m2[2][3]*m1[0][5]*m0[1][4]-m2[2][3]*m1[0][4]*m0[1][5]+m2[2][1]*m1[1][5]*m0[0][5]-m2[2][1]*m1[0][5]*m0[1][5]-m2[1][5]*m1[2][5]*m0[0][1]-m2[1][5]*m1[2][4]*m0[0][3]-m2[1][5]*m1[2][3]*m0[0][4]-m2[1][5]*m1[2][1]*m0[0][5]+m2[1][5]*m1[0][5]*m0[2][1]+m2[1][5]*m1[0][4]*m0[2][3]+m2[1][5]*m1[0][3]*m0[2][4]+m2[1][5]*m1[0][1]*m0[2][5]-m2[1][4]*m1[2][5]*m0[0][3]-m2[1][4]*m1[2][3]*m0[0][5]+m2[1][4]*m1[0][5]*m0[2][3]+m2[1][4]*m1[0][3]*m0[2][5]-m2[1][3]*m1[2][5]*m0[0][4]-m2[1][3]*m1[2][4]*m0[0][5]+m2[1][3]*m1[0][5]*m0[2][4]+m2[1][3]*m1[0][4]*m0[2][5]-m2[1][1]*m1[2][5]*m0[0][5]+m2[1][1]*m1[0][5]*m0[2][5]+m2[0][5]*m1[2][5]*m0[1][1]+m2[0][5]*m1[2][4]*m0[1][3]+m2[0][5]*m1[2][3]*m0[1][4]+m2[0][5]*m1[2][1]*m0[1][5]-m2[0][5]*m1[1][5]*m0[2][1]-m2[0][5]*m1[1][4]*m0[2][3]-m2[0][5]*m1[1][3]*m0[2][4]-m2[0][5]*m1[1][1]*m0[2][5]+m2[0][4]*m1[2][5]*m0[1][3]+m2[0][4]*m1[2][3]*m0[1][5]-m2[0][4]*m1[1][5]*m0[2][3]-m2[0][4]*m1[1][3]*m0[2][5]+m2[0][3]*m1[2][5]*m0[1][4]+m2[0][3]*m1[2][4]*m0[1][5]-m2[0][3]*m1[1][5]*m0[2][4]-m2[0][3]*m1[1][4]*m0[2][5]+m2[0][1]*m1[2][5]*m0[1][5]-m2[0][1]*m1[1][5]*m0[2][5]; M1(row,24) = m2[2][5]*m1[1][5]*m0[0][2]+m2[2][5]*m1[1][4]*m0[0][4]+m2[2][5]*m1[1][2]*m0[0][5]-m2[2][5]*m1[0][5]*m0[1][2]-m2[2][5]*m1[0][4]*m0[1][4]-m2[2][5]*m1[0][2]*m0[1][5]+m2[2][4]*m1[1][5]*m0[0][4]+m2[2][4]*m1[1][4]*m0[0][5]-m2[2][4]*m1[0][5]*m0[1][4]-m2[2][4]*m1[0][4]*m0[1][5]+m2[2][2]*m1[1][5]*m0[0][5]-m2[2][2]*m1[0][5]*m0[1][5]-m2[1][5]*m1[2][5]*m0[0][2]-m2[1][5]*m1[2][4]*m0[0][4]-m2[1][5]*m1[2][2]*m0[0][5]+m2[1][5]*m1[0][5]*m0[2][2]+m2[1][5]*m1[0][4]*m0[2][4]+m2[1][5]*m1[0][2]*m0[2][5]-m2[1][4]*m1[2][5]*m0[0][4]-m2[1][4]*m1[2][4]*m0[0][5]+m2[1][4]*m1[0][5]*m0[2][4]+m2[1][4]*m1[0][4]*m0[2][5]-m2[1][2]*m1[2][5]*m0[0][5]+m2[1][2]*m1[0][5]*m0[2][5]+m2[0][5]*m1[2][5]*m0[1][2]+m2[0][5]*m1[2][4]*m0[1][4]+m2[0][5]*m1[2][2]*m0[1][5]-m2[0][5]*m1[1][5]*m0[2][2]-m2[0][5]*m1[1][4]*m0[2][4]-m2[0][5]*m1[1][2]*m0[2][5]+m2[0][4]*m1[2][5]*m0[1][4]+m2[0][4]*m1[2][4]*m0[1][5]-m2[0][4]*m1[1][5]*m0[2][4]-m2[0][4]*m1[1][4]*m0[2][5]+m2[0][2]*m1[2][5]*m0[1][5]-m2[0][2]*m1[1][5]*m0[2][5]; M1(row,25) = m2[2][5]*m1[1][5]*m0[0][3]+m2[2][5]*m1[1][3]*m0[0][5]-m2[2][5]*m1[0][5]*m0[1][3]-m2[2][5]*m1[0][3]*m0[1][5]+m2[2][3]*m1[1][5]*m0[0][5]-m2[2][3]*m1[0][5]*m0[1][5]-m2[1][5]*m1[2][5]*m0[0][3]-m2[1][5]*m1[2][3]*m0[0][5]+m2[1][5]*m1[0][5]*m0[2][3]+m2[1][5]*m1[0][3]*m0[2][5]-m2[1][3]*m1[2][5]*m0[0][5]+m2[1][3]*m1[0][5]*m0[2][5]+m2[0][5]*m1[2][5]*m0[1][3]+m2[0][5]*m1[2][3]*m0[1][5]-m2[0][5]*m1[1][5]*m0[2][3]-m2[0][5]*m1[1][3]*m0[2][5]+m2[0][3]*m1[2][5]*m0[1][5]-m2[0][3]*m1[1][5]*m0[2][5]; M1(row,26) = m2[2][5]*m1[1][5]*m0[0][4]+m2[2][5]*m1[1][4]*m0[0][5]-m2[2][5]*m1[0][5]*m0[1][4]-m2[2][5]*m1[0][4]*m0[1][5]+m2[2][4]*m1[1][5]*m0[0][5]-m2[2][4]*m1[0][5]*m0[1][5]-m2[1][5]*m1[2][5]*m0[0][4]-m2[1][5]*m1[2][4]*m0[0][5]+m2[1][5]*m1[0][5]*m0[2][4]+m2[1][5]*m1[0][4]*m0[2][5]-m2[1][4]*m1[2][5]*m0[0][5]+m2[1][4]*m1[0][5]*m0[2][5]+m2[0][5]*m1[2][5]*m0[1][4]+m2[0][5]*m1[2][4]*m0[1][5]-m2[0][5]*m1[1][5]*m0[2][4]-m2[0][5]*m1[1][4]*m0[2][5]+m2[0][4]*m1[2][5]*m0[1][5]-m2[0][4]*m1[1][5]*m0[2][5]; M1(row,27) = m2[2][5]*m1[1][5]*m0[0][5]-m2[2][5]*m1[0][5]*m0[1][5]-m2[1][5]*m1[2][5]*m0[0][5]+m2[1][5]*m1[0][5]*m0[2][5]+m2[0][5]*m1[2][5]*m0[1][5]-m2[0][5]*m1[1][5]*m0[2][5]; M1(row,28) = m2[2][6]*m1[1][0]*m0[0][0]-m2[2][6]*m1[0][0]*m0[1][0]+m2[2][0]*m1[1][6]*m0[0][0]+m2[2][0]*m1[1][0]*m0[0][6]-m2[2][0]*m1[0][6]*m0[1][0]-m2[2][0]*m1[0][0]*m0[1][6]-m2[1][6]*m1[2][0]*m0[0][0]+m2[1][6]*m1[0][0]*m0[2][0]-m2[1][0]*m1[2][6]*m0[0][0]-m2[1][0]*m1[2][0]*m0[0][6]+m2[1][0]*m1[0][6]*m0[2][0]+m2[1][0]*m1[0][0]*m0[2][6]+m2[0][6]*m1[2][0]*m0[1][0]-m2[0][6]*m1[1][0]*m0[2][0]+m2[0][0]*m1[2][6]*m0[1][0]+m2[0][0]*m1[2][0]*m0[1][6]-m2[0][0]*m1[1][6]*m0[2][0]-m2[0][0]*m1[1][0]*m0[2][6]; M1(row,29) = m2[2][7]*m1[1][0]*m0[0][0]-m2[2][7]*m1[0][0]*m0[1][0]+m2[2][6]*m1[1][1]*m0[0][0]+m2[2][6]*m1[1][0]*m0[0][1]-m2[2][6]*m1[0][1]*m0[1][0]-m2[2][6]*m1[0][0]*m0[1][1]+m2[2][1]*m1[1][6]*m0[0][0]+m2[2][1]*m1[1][0]*m0[0][6]-m2[2][1]*m1[0][6]*m0[1][0]-m2[2][1]*m1[0][0]*m0[1][6]+m2[2][0]*m1[1][7]*m0[0][0]+m2[2][0]*m1[1][6]*m0[0][1]+m2[2][0]*m1[1][1]*m0[0][6]+m2[2][0]*m1[1][0]*m0[0][7]-m2[2][0]*m1[0][7]*m0[1][0]-m2[2][0]*m1[0][6]*m0[1][1]-m2[2][0]*m1[0][1]*m0[1][6]-m2[2][0]*m1[0][0]*m0[1][7]-m2[1][7]*m1[2][0]*m0[0][0]+m2[1][7]*m1[0][0]*m0[2][0]-m2[1][6]*m1[2][1]*m0[0][0]-m2[1][6]*m1[2][0]*m0[0][1]+m2[1][6]*m1[0][1]*m0[2][0]+m2[1][6]*m1[0][0]*m0[2][1]-m2[1][1]*m1[2][6]*m0[0][0]-m2[1][1]*m1[2][0]*m0[0][6]+m2[1][1]*m1[0][6]*m0[2][0]+m2[1][1]*m1[0][0]*m0[2][6]-m2[1][0]*m1[2][7]*m0[0][0]-m2[1][0]*m1[2][6]*m0[0][1]-m2[1][0]*m1[2][1]*m0[0][6]-m2[1][0]*m1[2][0]*m0[0][7]+m2[1][0]*m1[0][7]*m0[2][0]+m2[1][0]*m1[0][6]*m0[2][1]+m2[1][0]*m1[0][1]*m0[2][6]+m2[1][0]*m1[0][0]*m0[2][7]+m2[0][7]*m1[2][0]*m0[1][0]-m2[0][7]*m1[1][0]*m0[2][0]+m2[0][6]*m1[2][1]*m0[1][0]+m2[0][6]*m1[2][0]*m0[1][1]-m2[0][6]*m1[1][1]*m0[2][0]-m2[0][6]*m1[1][0]*m0[2][1]+m2[0][1]*m1[2][6]*m0[1][0]+m2[0][1]*m1[2][0]*m0[1][6]-m2[0][1]*m1[1][6]*m0[2][0]-m2[0][1]*m1[1][0]*m0[2][6]+m2[0][0]*m1[2][7]*m0[1][0]+m2[0][0]*m1[2][6]*m0[1][1]+m2[0][0]*m1[2][1]*m0[1][6]+m2[0][0]*m1[2][0]*m0[1][7]-m2[0][0]*m1[1][7]*m0[2][0]-m2[0][0]*m1[1][6]*m0[2][1]-m2[0][0]*m1[1][1]*m0[2][6]-m2[0][0]*m1[1][0]*m0[2][7]; M1(row,30) = m2[2][7]*m1[1][1]*m0[0][0]+m2[2][7]*m1[1][0]*m0[0][1]-m2[2][7]*m1[0][1]*m0[1][0]-m2[2][7]*m1[0][0]*m0[1][1]+m2[2][6]*m1[1][2]*m0[0][0]+m2[2][6]*m1[1][1]*m0[0][1]+m2[2][6]*m1[1][0]*m0[0][2]-m2[2][6]*m1[0][2]*m0[1][0]-m2[2][6]*m1[0][1]*m0[1][1]-m2[2][6]*m1[0][0]*m0[1][2]+m2[2][2]*m1[1][6]*m0[0][0]+m2[2][2]*m1[1][0]*m0[0][6]-m2[2][2]*m1[0][6]*m0[1][0]-m2[2][2]*m1[0][0]*m0[1][6]+m2[2][1]*m1[1][7]*m0[0][0]+m2[2][1]*m1[1][6]*m0[0][1]+m2[2][1]*m1[1][1]*m0[0][6]+m2[2][1]*m1[1][0]*m0[0][7]-m2[2][1]*m1[0][7]*m0[1][0]-m2[2][1]*m1[0][6]*m0[1][1]-m2[2][1]*m1[0][1]*m0[1][6]-m2[2][1]*m1[0][0]*m0[1][7]+m2[2][0]*m1[1][7]*m0[0][1]+m2[2][0]*m1[1][6]*m0[0][2]+m2[2][0]*m1[1][2]*m0[0][6]+m2[2][0]*m1[1][1]*m0[0][7]-m2[2][0]*m1[0][7]*m0[1][1]-m2[2][0]*m1[0][6]*m0[1][2]-m2[2][0]*m1[0][2]*m0[1][6]-m2[2][0]*m1[0][1]*m0[1][7]-m2[1][7]*m1[2][1]*m0[0][0]-m2[1][7]*m1[2][0]*m0[0][1]+m2[1][7]*m1[0][1]*m0[2][0]+m2[1][7]*m1[0][0]*m0[2][1]-m2[1][6]*m1[2][2]*m0[0][0]-m2[1][6]*m1[2][1]*m0[0][1]-m2[1][6]*m1[2][0]*m0[0][2]+m2[1][6]*m1[0][2]*m0[2][0]+m2[1][6]*m1[0][1]*m0[2][1]+m2[1][6]*m1[0][0]*m0[2][2]-m2[1][2]*m1[2][6]*m0[0][0]-m2[1][2]*m1[2][0]*m0[0][6]+m2[1][2]*m1[0][6]*m0[2][0]+m2[1][2]*m1[0][0]*m0[2][6]-m2[1][1]*m1[2][7]*m0[0][0]-m2[1][1]*m1[2][6]*m0[0][1]-m2[1][1]*m1[2][1]*m0[0][6]-m2[1][1]*m1[2][0]*m0[0][7]+m2[1][1]*m1[0][7]*m0[2][0]+m2[1][1]*m1[0][6]*m0[2][1]+m2[1][1]*m1[0][1]*m0[2][6]+m2[1][1]*m1[0][0]*m0[2][7]-m2[1][0]*m1[2][7]*m0[0][1]-m2[1][0]*m1[2][6]*m0[0][2]-m2[1][0]*m1[2][2]*m0[0][6]-m2[1][0]*m1[2][1]*m0[0][7]+m2[1][0]*m1[0][7]*m0[2][1]+m2[1][0]*m1[0][6]*m0[2][2]+m2[1][0]*m1[0][2]*m0[2][6]+m2[1][0]*m1[0][1]*m0[2][7]+m2[0][7]*m1[2][1]*m0[1][0]+m2[0][7]*m1[2][0]*m0[1][1]-m2[0][7]*m1[1][1]*m0[2][0]-m2[0][7]*m1[1][0]*m0[2][1]+m2[0][6]*m1[2][2]*m0[1][0]+m2[0][6]*m1[2][1]*m0[1][1]+m2[0][6]*m1[2][0]*m0[1][2]-m2[0][6]*m1[1][2]*m0[2][0]-m2[0][6]*m1[1][1]*m0[2][1]-m2[0][6]*m1[1][0]*m0[2][2]+m2[0][2]*m1[2][6]*m0[1][0]+m2[0][2]*m1[2][0]*m0[1][6]-m2[0][2]*m1[1][6]*m0[2][0]-m2[0][2]*m1[1][0]*m0[2][6]+m2[0][1]*m1[2][7]*m0[1][0]+m2[0][1]*m1[2][6]*m0[1][1]+m2[0][1]*m1[2][1]*m0[1][6]+m2[0][1]*m1[2][0]*m0[1][7]-m2[0][1]*m1[1][7]*m0[2][0]-m2[0][1]*m1[1][6]*m0[2][1]-m2[0][1]*m1[1][1]*m0[2][6]-m2[0][1]*m1[1][0]*m0[2][7]+m2[0][0]*m1[2][7]*m0[1][1]+m2[0][0]*m1[2][6]*m0[1][2]+m2[0][0]*m1[2][2]*m0[1][6]+m2[0][0]*m1[2][1]*m0[1][7]-m2[0][0]*m1[1][7]*m0[2][1]-m2[0][0]*m1[1][6]*m0[2][2]-m2[0][0]*m1[1][2]*m0[2][6]-m2[0][0]*m1[1][1]*m0[2][7]; M1(row,31) = m2[2][7]*m1[1][2]*m0[0][0]+m2[2][7]*m1[1][1]*m0[0][1]+m2[2][7]*m1[1][0]*m0[0][2]-m2[2][7]*m1[0][2]*m0[1][0]-m2[2][7]*m1[0][1]*m0[1][1]-m2[2][7]*m1[0][0]*m0[1][2]+m2[2][6]*m1[1][2]*m0[0][1]+m2[2][6]*m1[1][1]*m0[0][2]-m2[2][6]*m1[0][2]*m0[1][1]-m2[2][6]*m1[0][1]*m0[1][2]+m2[2][2]*m1[1][7]*m0[0][0]+m2[2][2]*m1[1][6]*m0[0][1]+m2[2][2]*m1[1][1]*m0[0][6]+m2[2][2]*m1[1][0]*m0[0][7]-m2[2][2]*m1[0][7]*m0[1][0]-m2[2][2]*m1[0][6]*m0[1][1]-m2[2][2]*m1[0][1]*m0[1][6]-m2[2][2]*m1[0][0]*m0[1][7]+m2[2][1]*m1[1][7]*m0[0][1]+m2[2][1]*m1[1][6]*m0[0][2]+m2[2][1]*m1[1][2]*m0[0][6]+m2[2][1]*m1[1][1]*m0[0][7]-m2[2][1]*m1[0][7]*m0[1][1]-m2[2][1]*m1[0][6]*m0[1][2]-m2[2][1]*m1[0][2]*m0[1][6]-m2[2][1]*m1[0][1]*m0[1][7]+m2[2][0]*m1[1][7]*m0[0][2]+m2[2][0]*m1[1][2]*m0[0][7]-m2[2][0]*m1[0][7]*m0[1][2]-m2[2][0]*m1[0][2]*m0[1][7]-m2[1][7]*m1[2][2]*m0[0][0]-m2[1][7]*m1[2][1]*m0[0][1]-m2[1][7]*m1[2][0]*m0[0][2]+m2[1][7]*m1[0][2]*m0[2][0]+m2[1][7]*m1[0][1]*m0[2][1]+m2[1][7]*m1[0][0]*m0[2][2]-m2[1][6]*m1[2][2]*m0[0][1]-m2[1][6]*m1[2][1]*m0[0][2]+m2[1][6]*m1[0][2]*m0[2][1]+m2[1][6]*m1[0][1]*m0[2][2]-m2[1][2]*m1[2][7]*m0[0][0]-m2[1][2]*m1[2][6]*m0[0][1]-m2[1][2]*m1[2][1]*m0[0][6]-m2[1][2]*m1[2][0]*m0[0][7]+m2[1][2]*m1[0][7]*m0[2][0]+m2[1][2]*m1[0][6]*m0[2][1]+m2[1][2]*m1[0][1]*m0[2][6]+m2[1][2]*m1[0][0]*m0[2][7]-m2[1][1]*m1[2][7]*m0[0][1]-m2[1][1]*m1[2][6]*m0[0][2]-m2[1][1]*m1[2][2]*m0[0][6]-m2[1][1]*m1[2][1]*m0[0][7]+m2[1][1]*m1[0][7]*m0[2][1]+m2[1][1]*m1[0][6]*m0[2][2]+m2[1][1]*m1[0][2]*m0[2][6]+m2[1][1]*m1[0][1]*m0[2][7]-m2[1][0]*m1[2][7]*m0[0][2]-m2[1][0]*m1[2][2]*m0[0][7]+m2[1][0]*m1[0][7]*m0[2][2]+m2[1][0]*m1[0][2]*m0[2][7]+m2[0][7]*m1[2][2]*m0[1][0]+m2[0][7]*m1[2][1]*m0[1][1]+m2[0][7]*m1[2][0]*m0[1][2]-m2[0][7]*m1[1][2]*m0[2][0]-m2[0][7]*m1[1][1]*m0[2][1]-m2[0][7]*m1[1][0]*m0[2][2]+m2[0][6]*m1[2][2]*m0[1][1]+m2[0][6]*m1[2][1]*m0[1][2]-m2[0][6]*m1[1][2]*m0[2][1]-m2[0][6]*m1[1][1]*m0[2][2]+m2[0][2]*m1[2][7]*m0[1][0]+m2[0][2]*m1[2][6]*m0[1][1]+m2[0][2]*m1[2][1]*m0[1][6]+m2[0][2]*m1[2][0]*m0[1][7]-m2[0][2]*m1[1][7]*m0[2][0]-m2[0][2]*m1[1][6]*m0[2][1]-m2[0][2]*m1[1][1]*m0[2][6]-m2[0][2]*m1[1][0]*m0[2][7]+m2[0][1]*m1[2][7]*m0[1][1]+m2[0][1]*m1[2][6]*m0[1][2]+m2[0][1]*m1[2][2]*m0[1][6]+m2[0][1]*m1[2][1]*m0[1][7]-m2[0][1]*m1[1][7]*m0[2][1]-m2[0][1]*m1[1][6]*m0[2][2]-m2[0][1]*m1[1][2]*m0[2][6]-m2[0][1]*m1[1][1]*m0[2][7]+m2[0][0]*m1[2][7]*m0[1][2]+m2[0][0]*m1[2][2]*m0[1][7]-m2[0][0]*m1[1][7]*m0[2][2]-m2[0][0]*m1[1][2]*m0[2][7]; M1(row,32) = m2[2][7]*m1[1][2]*m0[0][1]+m2[2][7]*m1[1][1]*m0[0][2]-m2[2][7]*m1[0][2]*m0[1][1]-m2[2][7]*m1[0][1]*m0[1][2]+m2[2][6]*m1[1][2]*m0[0][2]-m2[2][6]*m1[0][2]*m0[1][2]+m2[2][2]*m1[1][7]*m0[0][1]+m2[2][2]*m1[1][6]*m0[0][2]+m2[2][2]*m1[1][2]*m0[0][6]+m2[2][2]*m1[1][1]*m0[0][7]-m2[2][2]*m1[0][7]*m0[1][1]-m2[2][2]*m1[0][6]*m0[1][2]-m2[2][2]*m1[0][2]*m0[1][6]-m2[2][2]*m1[0][1]*m0[1][7]+m2[2][1]*m1[1][7]*m0[0][2]+m2[2][1]*m1[1][2]*m0[0][7]-m2[2][1]*m1[0][7]*m0[1][2]-m2[2][1]*m1[0][2]*m0[1][7]-m2[1][7]*m1[2][2]*m0[0][1]-m2[1][7]*m1[2][1]*m0[0][2]+m2[1][7]*m1[0][2]*m0[2][1]+m2[1][7]*m1[0][1]*m0[2][2]-m2[1][6]*m1[2][2]*m0[0][2]+m2[1][6]*m1[0][2]*m0[2][2]-m2[1][2]*m1[2][7]*m0[0][1]-m2[1][2]*m1[2][6]*m0[0][2]-m2[1][2]*m1[2][2]*m0[0][6]-m2[1][2]*m1[2][1]*m0[0][7]+m2[1][2]*m1[0][7]*m0[2][1]+m2[1][2]*m1[0][6]*m0[2][2]+m2[1][2]*m1[0][2]*m0[2][6]+m2[1][2]*m1[0][1]*m0[2][7]-m2[1][1]*m1[2][7]*m0[0][2]-m2[1][1]*m1[2][2]*m0[0][7]+m2[1][1]*m1[0][7]*m0[2][2]+m2[1][1]*m1[0][2]*m0[2][7]+m2[0][7]*m1[2][2]*m0[1][1]+m2[0][7]*m1[2][1]*m0[1][2]-m2[0][7]*m1[1][2]*m0[2][1]-m2[0][7]*m1[1][1]*m0[2][2]+m2[0][6]*m1[2][2]*m0[1][2]-m2[0][6]*m1[1][2]*m0[2][2]+m2[0][2]*m1[2][7]*m0[1][1]+m2[0][2]*m1[2][6]*m0[1][2]+m2[0][2]*m1[2][2]*m0[1][6]+m2[0][2]*m1[2][1]*m0[1][7]-m2[0][2]*m1[1][7]*m0[2][1]-m2[0][2]*m1[1][6]*m0[2][2]-m2[0][2]*m1[1][2]*m0[2][6]-m2[0][2]*m1[1][1]*m0[2][7]+m2[0][1]*m1[2][7]*m0[1][2]+m2[0][1]*m1[2][2]*m0[1][7]-m2[0][1]*m1[1][7]*m0[2][2]-m2[0][1]*m1[1][2]*m0[2][7]; M1(row,33) = m2[2][7]*m1[1][2]*m0[0][2]-m2[2][7]*m1[0][2]*m0[1][2]+m2[2][2]*m1[1][7]*m0[0][2]+m2[2][2]*m1[1][2]*m0[0][7]-m2[2][2]*m1[0][7]*m0[1][2]-m2[2][2]*m1[0][2]*m0[1][7]-m2[1][7]*m1[2][2]*m0[0][2]+m2[1][7]*m1[0][2]*m0[2][2]-m2[1][2]*m1[2][7]*m0[0][2]-m2[1][2]*m1[2][2]*m0[0][7]+m2[1][2]*m1[0][7]*m0[2][2]+m2[1][2]*m1[0][2]*m0[2][7]+m2[0][7]*m1[2][2]*m0[1][2]-m2[0][7]*m1[1][2]*m0[2][2]+m2[0][2]*m1[2][7]*m0[1][2]+m2[0][2]*m1[2][2]*m0[1][7]-m2[0][2]*m1[1][7]*m0[2][2]-m2[0][2]*m1[1][2]*m0[2][7]; M1(row,34) = m2[2][8]*m1[1][0]*m0[0][0]-m2[2][8]*m1[0][0]*m0[1][0]+m2[2][6]*m1[1][3]*m0[0][0]+m2[2][6]*m1[1][0]*m0[0][3]-m2[2][6]*m1[0][3]*m0[1][0]-m2[2][6]*m1[0][0]*m0[1][3]+m2[2][3]*m1[1][6]*m0[0][0]+m2[2][3]*m1[1][0]*m0[0][6]-m2[2][3]*m1[0][6]*m0[1][0]-m2[2][3]*m1[0][0]*m0[1][6]+m2[2][0]*m1[1][8]*m0[0][0]+m2[2][0]*m1[1][6]*m0[0][3]+m2[2][0]*m1[1][3]*m0[0][6]+m2[2][0]*m1[1][0]*m0[0][8]-m2[2][0]*m1[0][8]*m0[1][0]-m2[2][0]*m1[0][6]*m0[1][3]-m2[2][0]*m1[0][3]*m0[1][6]-m2[2][0]*m1[0][0]*m0[1][8]-m2[1][8]*m1[2][0]*m0[0][0]+m2[1][8]*m1[0][0]*m0[2][0]-m2[1][6]*m1[2][3]*m0[0][0]-m2[1][6]*m1[2][0]*m0[0][3]+m2[1][6]*m1[0][3]*m0[2][0]+m2[1][6]*m1[0][0]*m0[2][3]-m2[1][3]*m1[2][6]*m0[0][0]-m2[1][3]*m1[2][0]*m0[0][6]+m2[1][3]*m1[0][6]*m0[2][0]+m2[1][3]*m1[0][0]*m0[2][6]-m2[1][0]*m1[2][8]*m0[0][0]-m2[1][0]*m1[2][6]*m0[0][3]-m2[1][0]*m1[2][3]*m0[0][6]-m2[1][0]*m1[2][0]*m0[0][8]+m2[1][0]*m1[0][8]*m0[2][0]+m2[1][0]*m1[0][6]*m0[2][3]+m2[1][0]*m1[0][3]*m0[2][6]+m2[1][0]*m1[0][0]*m0[2][8]+m2[0][8]*m1[2][0]*m0[1][0]-m2[0][8]*m1[1][0]*m0[2][0]+m2[0][6]*m1[2][3]*m0[1][0]+m2[0][6]*m1[2][0]*m0[1][3]-m2[0][6]*m1[1][3]*m0[2][0]-m2[0][6]*m1[1][0]*m0[2][3]+m2[0][3]*m1[2][6]*m0[1][0]+m2[0][3]*m1[2][0]*m0[1][6]-m2[0][3]*m1[1][6]*m0[2][0]-m2[0][3]*m1[1][0]*m0[2][6]+m2[0][0]*m1[2][8]*m0[1][0]+m2[0][0]*m1[2][6]*m0[1][3]+m2[0][0]*m1[2][3]*m0[1][6]+m2[0][0]*m1[2][0]*m0[1][8]-m2[0][0]*m1[1][8]*m0[2][0]-m2[0][0]*m1[1][6]*m0[2][3]-m2[0][0]*m1[1][3]*m0[2][6]-m2[0][0]*m1[1][0]*m0[2][8]; M1(row,35) = m2[2][8]*m1[1][1]*m0[0][0]+m2[2][8]*m1[1][0]*m0[0][1]-m2[2][8]*m1[0][1]*m0[1][0]-m2[2][8]*m1[0][0]*m0[1][1]+m2[2][7]*m1[1][3]*m0[0][0]+m2[2][7]*m1[1][0]*m0[0][3]-m2[2][7]*m1[0][3]*m0[1][0]-m2[2][7]*m1[0][0]*m0[1][3]+m2[2][6]*m1[1][4]*m0[0][0]+m2[2][6]*m1[1][3]*m0[0][1]+m2[2][6]*m1[1][1]*m0[0][3]+m2[2][6]*m1[1][0]*m0[0][4]-m2[2][6]*m1[0][4]*m0[1][0]-m2[2][6]*m1[0][3]*m0[1][1]-m2[2][6]*m1[0][1]*m0[1][3]-m2[2][6]*m1[0][0]*m0[1][4]+m2[2][4]*m1[1][6]*m0[0][0]+m2[2][4]*m1[1][0]*m0[0][6]-m2[2][4]*m1[0][6]*m0[1][0]-m2[2][4]*m1[0][0]*m0[1][6]+m2[2][3]*m1[1][7]*m0[0][0]+m2[2][3]*m1[1][6]*m0[0][1]+m2[2][3]*m1[1][1]*m0[0][6]+m2[2][3]*m1[1][0]*m0[0][7]-m2[2][3]*m1[0][7]*m0[1][0]-m2[2][3]*m1[0][6]*m0[1][1]-m2[2][3]*m1[0][1]*m0[1][6]-m2[2][3]*m1[0][0]*m0[1][7]+m2[2][1]*m1[1][8]*m0[0][0]+m2[2][1]*m1[1][6]*m0[0][3]+m2[2][1]*m1[1][3]*m0[0][6]+m2[2][1]*m1[1][0]*m0[0][8]-m2[2][1]*m1[0][8]*m0[1][0]-m2[2][1]*m1[0][6]*m0[1][3]-m2[2][1]*m1[0][3]*m0[1][6]-m2[2][1]*m1[0][0]*m0[1][8]+m2[2][0]*m1[1][8]*m0[0][1]+m2[2][0]*m1[1][7]*m0[0][3]+m2[2][0]*m1[1][6]*m0[0][4]+m2[2][0]*m1[1][4]*m0[0][6]+m2[2][0]*m1[1][3]*m0[0][7]+m2[2][0]*m1[1][1]*m0[0][8]-m2[2][0]*m1[0][8]*m0[1][1]-m2[2][0]*m1[0][7]*m0[1][3]-m2[2][0]*m1[0][6]*m0[1][4]-m2[2][0]*m1[0][4]*m0[1][6]-m2[2][0]*m1[0][3]*m0[1][7]-m2[2][0]*m1[0][1]*m0[1][8]-m2[1][8]*m1[2][1]*m0[0][0]-m2[1][8]*m1[2][0]*m0[0][1]+m2[1][8]*m1[0][1]*m0[2][0]+m2[1][8]*m1[0][0]*m0[2][1]-m2[1][7]*m1[2][3]*m0[0][0]-m2[1][7]*m1[2][0]*m0[0][3]+m2[1][7]*m1[0][3]*m0[2][0]+m2[1][7]*m1[0][0]*m0[2][3]-m2[1][6]*m1[2][4]*m0[0][0]-m2[1][6]*m1[2][3]*m0[0][1]-m2[1][6]*m1[2][1]*m0[0][3]-m2[1][6]*m1[2][0]*m0[0][4]+m2[1][6]*m1[0][4]*m0[2][0]+m2[1][6]*m1[0][3]*m0[2][1]+m2[1][6]*m1[0][1]*m0[2][3]+m2[1][6]*m1[0][0]*m0[2][4]-m2[1][4]*m1[2][6]*m0[0][0]-m2[1][4]*m1[2][0]*m0[0][6]+m2[1][4]*m1[0][6]*m0[2][0]+m2[1][4]*m1[0][0]*m0[2][6]-m2[1][3]*m1[2][7]*m0[0][0]-m2[1][3]*m1[2][6]*m0[0][1]-m2[1][3]*m1[2][1]*m0[0][6]-m2[1][3]*m1[2][0]*m0[0][7]+m2[1][3]*m1[0][7]*m0[2][0]+m2[1][3]*m1[0][6]*m0[2][1]+m2[1][3]*m1[0][1]*m0[2][6]+m2[1][3]*m1[0][0]*m0[2][7]-m2[1][1]*m1[2][8]*m0[0][0]-m2[1][1]*m1[2][6]*m0[0][3]-m2[1][1]*m1[2][3]*m0[0][6]-m2[1][1]*m1[2][0]*m0[0][8]+m2[1][1]*m1[0][8]*m0[2][0]+m2[1][1]*m1[0][6]*m0[2][3]+m2[1][1]*m1[0][3]*m0[2][6]+m2[1][1]*m1[0][0]*m0[2][8]-m2[1][0]*m1[2][8]*m0[0][1]-m2[1][0]*m1[2][7]*m0[0][3]-m2[1][0]*m1[2][6]*m0[0][4]-m2[1][0]*m1[2][4]*m0[0][6]-m2[1][0]*m1[2][3]*m0[0][7]-m2[1][0]*m1[2][1]*m0[0][8]+m2[1][0]*m1[0][8]*m0[2][1]+m2[1][0]*m1[0][7]*m0[2][3]+m2[1][0]*m1[0][6]*m0[2][4]+m2[1][0]*m1[0][4]*m0[2][6]+m2[1][0]*m1[0][3]*m0[2][7]+m2[1][0]*m1[0][1]*m0[2][8]+m2[0][8]*m1[2][1]*m0[1][0]+m2[0][8]*m1[2][0]*m0[1][1]-m2[0][8]*m1[1][1]*m0[2][0]-m2[0][8]*m1[1][0]*m0[2][1]+m2[0][7]*m1[2][3]*m0[1][0]+m2[0][7]*m1[2][0]*m0[1][3]-m2[0][7]*m1[1][3]*m0[2][0]-m2[0][7]*m1[1][0]*m0[2][3]+m2[0][6]*m1[2][4]*m0[1][0]+m2[0][6]*m1[2][3]*m0[1][1]+m2[0][6]*m1[2][1]*m0[1][3]+m2[0][6]*m1[2][0]*m0[1][4]-m2[0][6]*m1[1][4]*m0[2][0]-m2[0][6]*m1[1][3]*m0[2][1]-m2[0][6]*m1[1][1]*m0[2][3]-m2[0][6]*m1[1][0]*m0[2][4]+m2[0][4]*m1[2][6]*m0[1][0]+m2[0][4]*m1[2][0]*m0[1][6]-m2[0][4]*m1[1][6]*m0[2][0]-m2[0][4]*m1[1][0]*m0[2][6]+m2[0][3]*m1[2][7]*m0[1][0]+m2[0][3]*m1[2][6]*m0[1][1]+m2[0][3]*m1[2][1]*m0[1][6]+m2[0][3]*m1[2][0]*m0[1][7]-m2[0][3]*m1[1][7]*m0[2][0]-m2[0][3]*m1[1][6]*m0[2][1]-m2[0][3]*m1[1][1]*m0[2][6]-m2[0][3]*m1[1][0]*m0[2][7]+m2[0][1]*m1[2][8]*m0[1][0]+m2[0][1]*m1[2][6]*m0[1][3]+m2[0][1]*m1[2][3]*m0[1][6]+m2[0][1]*m1[2][0]*m0[1][8]-m2[0][1]*m1[1][8]*m0[2][0]-m2[0][1]*m1[1][6]*m0[2][3]-m2[0][1]*m1[1][3]*m0[2][6]-m2[0][1]*m1[1][0]*m0[2][8]+m2[0][0]*m1[2][8]*m0[1][1]+m2[0][0]*m1[2][7]*m0[1][3]+m2[0][0]*m1[2][6]*m0[1][4]+m2[0][0]*m1[2][4]*m0[1][6]+m2[0][0]*m1[2][3]*m0[1][7]+m2[0][0]*m1[2][1]*m0[1][8]-m2[0][0]*m1[1][8]*m0[2][1]-m2[0][0]*m1[1][7]*m0[2][3]-m2[0][0]*m1[1][6]*m0[2][4]-m2[0][0]*m1[1][4]*m0[2][6]-m2[0][0]*m1[1][3]*m0[2][7]-m2[0][0]*m1[1][1]*m0[2][8]; M1(row,36) = m2[2][8]*m1[1][2]*m0[0][0]+m2[2][8]*m1[1][1]*m0[0][1]+m2[2][8]*m1[1][0]*m0[0][2]-m2[2][8]*m1[0][2]*m0[1][0]-m2[2][8]*m1[0][1]*m0[1][1]-m2[2][8]*m1[0][0]*m0[1][2]+m2[2][7]*m1[1][4]*m0[0][0]+m2[2][7]*m1[1][3]*m0[0][1]+m2[2][7]*m1[1][1]*m0[0][3]+m2[2][7]*m1[1][0]*m0[0][4]-m2[2][7]*m1[0][4]*m0[1][0]-m2[2][7]*m1[0][3]*m0[1][1]-m2[2][7]*m1[0][1]*m0[1][3]-m2[2][7]*m1[0][0]*m0[1][4]+m2[2][6]*m1[1][4]*m0[0][1]+m2[2][6]*m1[1][3]*m0[0][2]+m2[2][6]*m1[1][2]*m0[0][3]+m2[2][6]*m1[1][1]*m0[0][4]-m2[2][6]*m1[0][4]*m0[1][1]-m2[2][6]*m1[0][3]*m0[1][2]-m2[2][6]*m1[0][2]*m0[1][3]-m2[2][6]*m1[0][1]*m0[1][4]+m2[2][4]*m1[1][7]*m0[0][0]+m2[2][4]*m1[1][6]*m0[0][1]+m2[2][4]*m1[1][1]*m0[0][6]+m2[2][4]*m1[1][0]*m0[0][7]-m2[2][4]*m1[0][7]*m0[1][0]-m2[2][4]*m1[0][6]*m0[1][1]-m2[2][4]*m1[0][1]*m0[1][6]-m2[2][4]*m1[0][0]*m0[1][7]+m2[2][3]*m1[1][7]*m0[0][1]+m2[2][3]*m1[1][6]*m0[0][2]+m2[2][3]*m1[1][2]*m0[0][6]+m2[2][3]*m1[1][1]*m0[0][7]-m2[2][3]*m1[0][7]*m0[1][1]-m2[2][3]*m1[0][6]*m0[1][2]-m2[2][3]*m1[0][2]*m0[1][6]-m2[2][3]*m1[0][1]*m0[1][7]+m2[2][2]*m1[1][8]*m0[0][0]+m2[2][2]*m1[1][6]*m0[0][3]+m2[2][2]*m1[1][3]*m0[0][6]+m2[2][2]*m1[1][0]*m0[0][8]-m2[2][2]*m1[0][8]*m0[1][0]-m2[2][2]*m1[0][6]*m0[1][3]-m2[2][2]*m1[0][3]*m0[1][6]-m2[2][2]*m1[0][0]*m0[1][8]+m2[2][1]*m1[1][8]*m0[0][1]+m2[2][1]*m1[1][7]*m0[0][3]+m2[2][1]*m1[1][6]*m0[0][4]+m2[2][1]*m1[1][4]*m0[0][6]+m2[2][1]*m1[1][3]*m0[0][7]+m2[2][1]*m1[1][1]*m0[0][8]-m2[2][1]*m1[0][8]*m0[1][1]-m2[2][1]*m1[0][7]*m0[1][3]-m2[2][1]*m1[0][6]*m0[1][4]-m2[2][1]*m1[0][4]*m0[1][6]-m2[2][1]*m1[0][3]*m0[1][7]-m2[2][1]*m1[0][1]*m0[1][8]+m2[2][0]*m1[1][8]*m0[0][2]+m2[2][0]*m1[1][7]*m0[0][4]+m2[2][0]*m1[1][4]*m0[0][7]+m2[2][0]*m1[1][2]*m0[0][8]-m2[2][0]*m1[0][8]*m0[1][2]-m2[2][0]*m1[0][7]*m0[1][4]-m2[2][0]*m1[0][4]*m0[1][7]-m2[2][0]*m1[0][2]*m0[1][8]-m2[1][8]*m1[2][2]*m0[0][0]-m2[1][8]*m1[2][1]*m0[0][1]-m2[1][8]*m1[2][0]*m0[0][2]+m2[1][8]*m1[0][2]*m0[2][0]+m2[1][8]*m1[0][1]*m0[2][1]+m2[1][8]*m1[0][0]*m0[2][2]-m2[1][7]*m1[2][4]*m0[0][0]-m2[1][7]*m1[2][3]*m0[0][1]-m2[1][7]*m1[2][1]*m0[0][3]-m2[1][7]*m1[2][0]*m0[0][4]+m2[1][7]*m1[0][4]*m0[2][0]+m2[1][7]*m1[0][3]*m0[2][1]+m2[1][7]*m1[0][1]*m0[2][3]+m2[1][7]*m1[0][0]*m0[2][4]-m2[1][6]*m1[2][4]*m0[0][1]-m2[1][6]*m1[2][3]*m0[0][2]-m2[1][6]*m1[2][2]*m0[0][3]-m2[1][6]*m1[2][1]*m0[0][4]+m2[1][6]*m1[0][4]*m0[2][1]+m2[1][6]*m1[0][3]*m0[2][2]+m2[1][6]*m1[0][2]*m0[2][3]+m2[1][6]*m1[0][1]*m0[2][4]-m2[1][4]*m1[2][7]*m0[0][0]-m2[1][4]*m1[2][6]*m0[0][1]-m2[1][4]*m1[2][1]*m0[0][6]-m2[1][4]*m1[2][0]*m0[0][7]+m2[1][4]*m1[0][7]*m0[2][0]+m2[1][4]*m1[0][6]*m0[2][1]+m2[1][4]*m1[0][1]*m0[2][6]+m2[1][4]*m1[0][0]*m0[2][7]-m2[1][3]*m1[2][7]*m0[0][1]-m2[1][3]*m1[2][6]*m0[0][2]-m2[1][3]*m1[2][2]*m0[0][6]-m2[1][3]*m1[2][1]*m0[0][7]+m2[1][3]*m1[0][7]*m0[2][1]+m2[1][3]*m1[0][6]*m0[2][2]+m2[1][3]*m1[0][2]*m0[2][6]+m2[1][3]*m1[0][1]*m0[2][7]-m2[1][2]*m1[2][8]*m0[0][0]-m2[1][2]*m1[2][6]*m0[0][3]-m2[1][2]*m1[2][3]*m0[0][6]-m2[1][2]*m1[2][0]*m0[0][8]+m2[1][2]*m1[0][8]*m0[2][0]+m2[1][2]*m1[0][6]*m0[2][3]+m2[1][2]*m1[0][3]*m0[2][6]+m2[1][2]*m1[0][0]*m0[2][8]-m2[1][1]*m1[2][8]*m0[0][1]-m2[1][1]*m1[2][7]*m0[0][3]-m2[1][1]*m1[2][6]*m0[0][4]-m2[1][1]*m1[2][4]*m0[0][6]-m2[1][1]*m1[2][3]*m0[0][7]-m2[1][1]*m1[2][1]*m0[0][8]+m2[1][1]*m1[0][8]*m0[2][1]+m2[1][1]*m1[0][7]*m0[2][3]+m2[1][1]*m1[0][6]*m0[2][4]+m2[1][1]*m1[0][4]*m0[2][6]+m2[1][1]*m1[0][3]*m0[2][7]+m2[1][1]*m1[0][1]*m0[2][8]-m2[1][0]*m1[2][8]*m0[0][2]-m2[1][0]*m1[2][7]*m0[0][4]-m2[1][0]*m1[2][4]*m0[0][7]-m2[1][0]*m1[2][2]*m0[0][8]+m2[1][0]*m1[0][8]*m0[2][2]+m2[1][0]*m1[0][7]*m0[2][4]+m2[1][0]*m1[0][4]*m0[2][7]+m2[1][0]*m1[0][2]*m0[2][8]+m2[0][8]*m1[2][2]*m0[1][0]+m2[0][8]*m1[2][1]*m0[1][1]+m2[0][8]*m1[2][0]*m0[1][2]-m2[0][8]*m1[1][2]*m0[2][0]-m2[0][8]*m1[1][1]*m0[2][1]-m2[0][8]*m1[1][0]*m0[2][2]+m2[0][7]*m1[2][4]*m0[1][0]+m2[0][7]*m1[2][3]*m0[1][1]+m2[0][7]*m1[2][1]*m0[1][3]+m2[0][7]*m1[2][0]*m0[1][4]-m2[0][7]*m1[1][4]*m0[2][0]-m2[0][7]*m1[1][3]*m0[2][1]-m2[0][7]*m1[1][1]*m0[2][3]-m2[0][7]*m1[1][0]*m0[2][4]+m2[0][6]*m1[2][4]*m0[1][1]+m2[0][6]*m1[2][3]*m0[1][2]+m2[0][6]*m1[2][2]*m0[1][3]+m2[0][6]*m1[2][1]*m0[1][4]-m2[0][6]*m1[1][4]*m0[2][1]-m2[0][6]*m1[1][3]*m0[2][2]-m2[0][6]*m1[1][2]*m0[2][3]-m2[0][6]*m1[1][1]*m0[2][4]+m2[0][4]*m1[2][7]*m0[1][0]+m2[0][4]*m1[2][6]*m0[1][1]+m2[0][4]*m1[2][1]*m0[1][6]+m2[0][4]*m1[2][0]*m0[1][7]-m2[0][4]*m1[1][7]*m0[2][0]-m2[0][4]*m1[1][6]*m0[2][1]-m2[0][4]*m1[1][1]*m0[2][6]-m2[0][4]*m1[1][0]*m0[2][7]+m2[0][3]*m1[2][7]*m0[1][1]+m2[0][3]*m1[2][6]*m0[1][2]+m2[0][3]*m1[2][2]*m0[1][6]+m2[0][3]*m1[2][1]*m0[1][7]-m2[0][3]*m1[1][7]*m0[2][1]-m2[0][3]*m1[1][6]*m0[2][2]-m2[0][3]*m1[1][2]*m0[2][6]-m2[0][3]*m1[1][1]*m0[2][7]+m2[0][2]*m1[2][8]*m0[1][0]+m2[0][2]*m1[2][6]*m0[1][3]+m2[0][2]*m1[2][3]*m0[1][6]+m2[0][2]*m1[2][0]*m0[1][8]-m2[0][2]*m1[1][8]*m0[2][0]-m2[0][2]*m1[1][6]*m0[2][3]-m2[0][2]*m1[1][3]*m0[2][6]-m2[0][2]*m1[1][0]*m0[2][8]+m2[0][1]*m1[2][8]*m0[1][1]+m2[0][1]*m1[2][7]*m0[1][3]+m2[0][1]*m1[2][6]*m0[1][4]+m2[0][1]*m1[2][4]*m0[1][6]+m2[0][1]*m1[2][3]*m0[1][7]+m2[0][1]*m1[2][1]*m0[1][8]-m2[0][1]*m1[1][8]*m0[2][1]-m2[0][1]*m1[1][7]*m0[2][3]-m2[0][1]*m1[1][6]*m0[2][4]-m2[0][1]*m1[1][4]*m0[2][6]-m2[0][1]*m1[1][3]*m0[2][7]-m2[0][1]*m1[1][1]*m0[2][8]+m2[0][0]*m1[2][8]*m0[1][2]+m2[0][0]*m1[2][7]*m0[1][4]+m2[0][0]*m1[2][4]*m0[1][7]+m2[0][0]*m1[2][2]*m0[1][8]-m2[0][0]*m1[1][8]*m0[2][2]-m2[0][0]*m1[1][7]*m0[2][4]-m2[0][0]*m1[1][4]*m0[2][7]-m2[0][0]*m1[1][2]*m0[2][8]; M1(row,37) = m2[2][8]*m1[1][2]*m0[0][1]+m2[2][8]*m1[1][1]*m0[0][2]-m2[2][8]*m1[0][2]*m0[1][1]-m2[2][8]*m1[0][1]*m0[1][2]+m2[2][7]*m1[1][4]*m0[0][1]+m2[2][7]*m1[1][3]*m0[0][2]+m2[2][7]*m1[1][2]*m0[0][3]+m2[2][7]*m1[1][1]*m0[0][4]-m2[2][7]*m1[0][4]*m0[1][1]-m2[2][7]*m1[0][3]*m0[1][2]-m2[2][7]*m1[0][2]*m0[1][3]-m2[2][7]*m1[0][1]*m0[1][4]+m2[2][6]*m1[1][4]*m0[0][2]+m2[2][6]*m1[1][2]*m0[0][4]-m2[2][6]*m1[0][4]*m0[1][2]-m2[2][6]*m1[0][2]*m0[1][4]+m2[2][4]*m1[1][7]*m0[0][1]+m2[2][4]*m1[1][6]*m0[0][2]+m2[2][4]*m1[1][2]*m0[0][6]+m2[2][4]*m1[1][1]*m0[0][7]-m2[2][4]*m1[0][7]*m0[1][1]-m2[2][4]*m1[0][6]*m0[1][2]-m2[2][4]*m1[0][2]*m0[1][6]-m2[2][4]*m1[0][1]*m0[1][7]+m2[2][3]*m1[1][7]*m0[0][2]+m2[2][3]*m1[1][2]*m0[0][7]-m2[2][3]*m1[0][7]*m0[1][2]-m2[2][3]*m1[0][2]*m0[1][7]+m2[2][2]*m1[1][8]*m0[0][1]+m2[2][2]*m1[1][7]*m0[0][3]+m2[2][2]*m1[1][6]*m0[0][4]+m2[2][2]*m1[1][4]*m0[0][6]+m2[2][2]*m1[1][3]*m0[0][7]+m2[2][2]*m1[1][1]*m0[0][8]-m2[2][2]*m1[0][8]*m0[1][1]-m2[2][2]*m1[0][7]*m0[1][3]-m2[2][2]*m1[0][6]*m0[1][4]-m2[2][2]*m1[0][4]*m0[1][6]-m2[2][2]*m1[0][3]*m0[1][7]-m2[2][2]*m1[0][1]*m0[1][8]+m2[2][1]*m1[1][8]*m0[0][2]+m2[2][1]*m1[1][7]*m0[0][4]+m2[2][1]*m1[1][4]*m0[0][7]+m2[2][1]*m1[1][2]*m0[0][8]-m2[2][1]*m1[0][8]*m0[1][2]-m2[2][1]*m1[0][7]*m0[1][4]-m2[2][1]*m1[0][4]*m0[1][7]-m2[2][1]*m1[0][2]*m0[1][8]-m2[1][8]*m1[2][2]*m0[0][1]-m2[1][8]*m1[2][1]*m0[0][2]+m2[1][8]*m1[0][2]*m0[2][1]+m2[1][8]*m1[0][1]*m0[2][2]-m2[1][7]*m1[2][4]*m0[0][1]-m2[1][7]*m1[2][3]*m0[0][2]-m2[1][7]*m1[2][2]*m0[0][3]-m2[1][7]*m1[2][1]*m0[0][4]+m2[1][7]*m1[0][4]*m0[2][1]+m2[1][7]*m1[0][3]*m0[2][2]+m2[1][7]*m1[0][2]*m0[2][3]+m2[1][7]*m1[0][1]*m0[2][4]-m2[1][6]*m1[2][4]*m0[0][2]-m2[1][6]*m1[2][2]*m0[0][4]+m2[1][6]*m1[0][4]*m0[2][2]+m2[1][6]*m1[0][2]*m0[2][4]-m2[1][4]*m1[2][7]*m0[0][1]-m2[1][4]*m1[2][6]*m0[0][2]-m2[1][4]*m1[2][2]*m0[0][6]-m2[1][4]*m1[2][1]*m0[0][7]+m2[1][4]*m1[0][7]*m0[2][1]+m2[1][4]*m1[0][6]*m0[2][2]+m2[1][4]*m1[0][2]*m0[2][6]+m2[1][4]*m1[0][1]*m0[2][7]-m2[1][3]*m1[2][7]*m0[0][2]-m2[1][3]*m1[2][2]*m0[0][7]+m2[1][3]*m1[0][7]*m0[2][2]+m2[1][3]*m1[0][2]*m0[2][7]-m2[1][2]*m1[2][8]*m0[0][1]-m2[1][2]*m1[2][7]*m0[0][3]-m2[1][2]*m1[2][6]*m0[0][4]-m2[1][2]*m1[2][4]*m0[0][6]-m2[1][2]*m1[2][3]*m0[0][7]-m2[1][2]*m1[2][1]*m0[0][8]+m2[1][2]*m1[0][8]*m0[2][1]+m2[1][2]*m1[0][7]*m0[2][3]+m2[1][2]*m1[0][6]*m0[2][4]+m2[1][2]*m1[0][4]*m0[2][6]+m2[1][2]*m1[0][3]*m0[2][7]+m2[1][2]*m1[0][1]*m0[2][8]-m2[1][1]*m1[2][8]*m0[0][2]-m2[1][1]*m1[2][7]*m0[0][4]-m2[1][1]*m1[2][4]*m0[0][7]-m2[1][1]*m1[2][2]*m0[0][8]+m2[1][1]*m1[0][8]*m0[2][2]+m2[1][1]*m1[0][7]*m0[2][4]+m2[1][1]*m1[0][4]*m0[2][7]+m2[1][1]*m1[0][2]*m0[2][8]+m2[0][8]*m1[2][2]*m0[1][1]+m2[0][8]*m1[2][1]*m0[1][2]-m2[0][8]*m1[1][2]*m0[2][1]-m2[0][8]*m1[1][1]*m0[2][2]+m2[0][7]*m1[2][4]*m0[1][1]+m2[0][7]*m1[2][3]*m0[1][2]+m2[0][7]*m1[2][2]*m0[1][3]+m2[0][7]*m1[2][1]*m0[1][4]-m2[0][7]*m1[1][4]*m0[2][1]-m2[0][7]*m1[1][3]*m0[2][2]-m2[0][7]*m1[1][2]*m0[2][3]-m2[0][7]*m1[1][1]*m0[2][4]+m2[0][6]*m1[2][4]*m0[1][2]+m2[0][6]*m1[2][2]*m0[1][4]-m2[0][6]*m1[1][4]*m0[2][2]-m2[0][6]*m1[1][2]*m0[2][4]+m2[0][4]*m1[2][7]*m0[1][1]+m2[0][4]*m1[2][6]*m0[1][2]+m2[0][4]*m1[2][2]*m0[1][6]+m2[0][4]*m1[2][1]*m0[1][7]-m2[0][4]*m1[1][7]*m0[2][1]-m2[0][4]*m1[1][6]*m0[2][2]-m2[0][4]*m1[1][2]*m0[2][6]-m2[0][4]*m1[1][1]*m0[2][7]+m2[0][3]*m1[2][7]*m0[1][2]+m2[0][3]*m1[2][2]*m0[1][7]-m2[0][3]*m1[1][7]*m0[2][2]-m2[0][3]*m1[1][2]*m0[2][7]+m2[0][2]*m1[2][8]*m0[1][1]+m2[0][2]*m1[2][7]*m0[1][3]+m2[0][2]*m1[2][6]*m0[1][4]+m2[0][2]*m1[2][4]*m0[1][6]+m2[0][2]*m1[2][3]*m0[1][7]+m2[0][2]*m1[2][1]*m0[1][8]-m2[0][2]*m1[1][8]*m0[2][1]-m2[0][2]*m1[1][7]*m0[2][3]-m2[0][2]*m1[1][6]*m0[2][4]-m2[0][2]*m1[1][4]*m0[2][6]-m2[0][2]*m1[1][3]*m0[2][7]-m2[0][2]*m1[1][1]*m0[2][8]+m2[0][1]*m1[2][8]*m0[1][2]+m2[0][1]*m1[2][7]*m0[1][4]+m2[0][1]*m1[2][4]*m0[1][7]+m2[0][1]*m1[2][2]*m0[1][8]-m2[0][1]*m1[1][8]*m0[2][2]-m2[0][1]*m1[1][7]*m0[2][4]-m2[0][1]*m1[1][4]*m0[2][7]-m2[0][1]*m1[1][2]*m0[2][8]; M1(row,38) = m2[2][8]*m1[1][2]*m0[0][2]-m2[2][8]*m1[0][2]*m0[1][2]+m2[2][7]*m1[1][4]*m0[0][2]+m2[2][7]*m1[1][2]*m0[0][4]-m2[2][7]*m1[0][4]*m0[1][2]-m2[2][7]*m1[0][2]*m0[1][4]+m2[2][4]*m1[1][7]*m0[0][2]+m2[2][4]*m1[1][2]*m0[0][7]-m2[2][4]*m1[0][7]*m0[1][2]-m2[2][4]*m1[0][2]*m0[1][7]+m2[2][2]*m1[1][8]*m0[0][2]+m2[2][2]*m1[1][7]*m0[0][4]+m2[2][2]*m1[1][4]*m0[0][7]+m2[2][2]*m1[1][2]*m0[0][8]-m2[2][2]*m1[0][8]*m0[1][2]-m2[2][2]*m1[0][7]*m0[1][4]-m2[2][2]*m1[0][4]*m0[1][7]-m2[2][2]*m1[0][2]*m0[1][8]-m2[1][8]*m1[2][2]*m0[0][2]+m2[1][8]*m1[0][2]*m0[2][2]-m2[1][7]*m1[2][4]*m0[0][2]-m2[1][7]*m1[2][2]*m0[0][4]+m2[1][7]*m1[0][4]*m0[2][2]+m2[1][7]*m1[0][2]*m0[2][4]-m2[1][4]*m1[2][7]*m0[0][2]-m2[1][4]*m1[2][2]*m0[0][7]+m2[1][4]*m1[0][7]*m0[2][2]+m2[1][4]*m1[0][2]*m0[2][7]-m2[1][2]*m1[2][8]*m0[0][2]-m2[1][2]*m1[2][7]*m0[0][4]-m2[1][2]*m1[2][4]*m0[0][7]-m2[1][2]*m1[2][2]*m0[0][8]+m2[1][2]*m1[0][8]*m0[2][2]+m2[1][2]*m1[0][7]*m0[2][4]+m2[1][2]*m1[0][4]*m0[2][7]+m2[1][2]*m1[0][2]*m0[2][8]+m2[0][8]*m1[2][2]*m0[1][2]-m2[0][8]*m1[1][2]*m0[2][2]+m2[0][7]*m1[2][4]*m0[1][2]+m2[0][7]*m1[2][2]*m0[1][4]-m2[0][7]*m1[1][4]*m0[2][2]-m2[0][7]*m1[1][2]*m0[2][4]+m2[0][4]*m1[2][7]*m0[1][2]+m2[0][4]*m1[2][2]*m0[1][7]-m2[0][4]*m1[1][7]*m0[2][2]-m2[0][4]*m1[1][2]*m0[2][7]+m2[0][2]*m1[2][8]*m0[1][2]+m2[0][2]*m1[2][7]*m0[1][4]+m2[0][2]*m1[2][4]*m0[1][7]+m2[0][2]*m1[2][2]*m0[1][8]-m2[0][2]*m1[1][8]*m0[2][2]-m2[0][2]*m1[1][7]*m0[2][4]-m2[0][2]*m1[1][4]*m0[2][7]-m2[0][2]*m1[1][2]*m0[2][8]; M1(row,39) = m2[2][8]*m1[1][3]*m0[0][0]+m2[2][8]*m1[1][0]*m0[0][3]-m2[2][8]*m1[0][3]*m0[1][0]-m2[2][8]*m1[0][0]*m0[1][3]+m2[2][6]*m1[1][5]*m0[0][0]+m2[2][6]*m1[1][3]*m0[0][3]+m2[2][6]*m1[1][0]*m0[0][5]-m2[2][6]*m1[0][5]*m0[1][0]-m2[2][6]*m1[0][3]*m0[1][3]-m2[2][6]*m1[0][0]*m0[1][5]+m2[2][5]*m1[1][6]*m0[0][0]+m2[2][5]*m1[1][0]*m0[0][6]-m2[2][5]*m1[0][6]*m0[1][0]-m2[2][5]*m1[0][0]*m0[1][6]+m2[2][3]*m1[1][8]*m0[0][0]+m2[2][3]*m1[1][6]*m0[0][3]+m2[2][3]*m1[1][3]*m0[0][6]+m2[2][3]*m1[1][0]*m0[0][8]-m2[2][3]*m1[0][8]*m0[1][0]-m2[2][3]*m1[0][6]*m0[1][3]-m2[2][3]*m1[0][3]*m0[1][6]-m2[2][3]*m1[0][0]*m0[1][8]+m2[2][0]*m1[1][8]*m0[0][3]+m2[2][0]*m1[1][6]*m0[0][5]+m2[2][0]*m1[1][5]*m0[0][6]+m2[2][0]*m1[1][3]*m0[0][8]-m2[2][0]*m1[0][8]*m0[1][3]-m2[2][0]*m1[0][6]*m0[1][5]-m2[2][0]*m1[0][5]*m0[1][6]-m2[2][0]*m1[0][3]*m0[1][8]-m2[1][8]*m1[2][3]*m0[0][0]-m2[1][8]*m1[2][0]*m0[0][3]+m2[1][8]*m1[0][3]*m0[2][0]+m2[1][8]*m1[0][0]*m0[2][3]-m2[1][6]*m1[2][5]*m0[0][0]-m2[1][6]*m1[2][3]*m0[0][3]-m2[1][6]*m1[2][0]*m0[0][5]+m2[1][6]*m1[0][5]*m0[2][0]+m2[1][6]*m1[0][3]*m0[2][3]+m2[1][6]*m1[0][0]*m0[2][5]-m2[1][5]*m1[2][6]*m0[0][0]-m2[1][5]*m1[2][0]*m0[0][6]+m2[1][5]*m1[0][6]*m0[2][0]+m2[1][5]*m1[0][0]*m0[2][6]-m2[1][3]*m1[2][8]*m0[0][0]-m2[1][3]*m1[2][6]*m0[0][3]-m2[1][3]*m1[2][3]*m0[0][6]-m2[1][3]*m1[2][0]*m0[0][8]+m2[1][3]*m1[0][8]*m0[2][0]+m2[1][3]*m1[0][6]*m0[2][3]+m2[1][3]*m1[0][3]*m0[2][6]+m2[1][3]*m1[0][0]*m0[2][8]-m2[1][0]*m1[2][8]*m0[0][3]-m2[1][0]*m1[2][6]*m0[0][5]-m2[1][0]*m1[2][5]*m0[0][6]-m2[1][0]*m1[2][3]*m0[0][8]+m2[1][0]*m1[0][8]*m0[2][3]+m2[1][0]*m1[0][6]*m0[2][5]+m2[1][0]*m1[0][5]*m0[2][6]+m2[1][0]*m1[0][3]*m0[2][8]+m2[0][8]*m1[2][3]*m0[1][0]+m2[0][8]*m1[2][0]*m0[1][3]-m2[0][8]*m1[1][3]*m0[2][0]-m2[0][8]*m1[1][0]*m0[2][3]+m2[0][6]*m1[2][5]*m0[1][0]+m2[0][6]*m1[2][3]*m0[1][3]+m2[0][6]*m1[2][0]*m0[1][5]-m2[0][6]*m1[1][5]*m0[2][0]-m2[0][6]*m1[1][3]*m0[2][3]-m2[0][6]*m1[1][0]*m0[2][5]+m2[0][5]*m1[2][6]*m0[1][0]+m2[0][5]*m1[2][0]*m0[1][6]-m2[0][5]*m1[1][6]*m0[2][0]-m2[0][5]*m1[1][0]*m0[2][6]+m2[0][3]*m1[2][8]*m0[1][0]+m2[0][3]*m1[2][6]*m0[1][3]+m2[0][3]*m1[2][3]*m0[1][6]+m2[0][3]*m1[2][0]*m0[1][8]-m2[0][3]*m1[1][8]*m0[2][0]-m2[0][3]*m1[1][6]*m0[2][3]-m2[0][3]*m1[1][3]*m0[2][6]-m2[0][3]*m1[1][0]*m0[2][8]+m2[0][0]*m1[2][8]*m0[1][3]+m2[0][0]*m1[2][6]*m0[1][5]+m2[0][0]*m1[2][5]*m0[1][6]+m2[0][0]*m1[2][3]*m0[1][8]-m2[0][0]*m1[1][8]*m0[2][3]-m2[0][0]*m1[1][6]*m0[2][5]-m2[0][0]*m1[1][5]*m0[2][6]-m2[0][0]*m1[1][3]*m0[2][8]; M1(row,40) = m2[2][8]*m1[1][4]*m0[0][0]+m2[2][8]*m1[1][3]*m0[0][1]+m2[2][8]*m1[1][1]*m0[0][3]+m2[2][8]*m1[1][0]*m0[0][4]-m2[2][8]*m1[0][4]*m0[1][0]-m2[2][8]*m1[0][3]*m0[1][1]-m2[2][8]*m1[0][1]*m0[1][3]-m2[2][8]*m1[0][0]*m0[1][4]+m2[2][7]*m1[1][5]*m0[0][0]+m2[2][7]*m1[1][3]*m0[0][3]+m2[2][7]*m1[1][0]*m0[0][5]-m2[2][7]*m1[0][5]*m0[1][0]-m2[2][7]*m1[0][3]*m0[1][3]-m2[2][7]*m1[0][0]*m0[1][5]+m2[2][6]*m1[1][5]*m0[0][1]+m2[2][6]*m1[1][4]*m0[0][3]+m2[2][6]*m1[1][3]*m0[0][4]+m2[2][6]*m1[1][1]*m0[0][5]-m2[2][6]*m1[0][5]*m0[1][1]-m2[2][6]*m1[0][4]*m0[1][3]-m2[2][6]*m1[0][3]*m0[1][4]-m2[2][6]*m1[0][1]*m0[1][5]+m2[2][5]*m1[1][7]*m0[0][0]+m2[2][5]*m1[1][6]*m0[0][1]+m2[2][5]*m1[1][1]*m0[0][6]+m2[2][5]*m1[1][0]*m0[0][7]-m2[2][5]*m1[0][7]*m0[1][0]-m2[2][5]*m1[0][6]*m0[1][1]-m2[2][5]*m1[0][1]*m0[1][6]-m2[2][5]*m1[0][0]*m0[1][7]+m2[2][4]*m1[1][8]*m0[0][0]+m2[2][4]*m1[1][6]*m0[0][3]+m2[2][4]*m1[1][3]*m0[0][6]+m2[2][4]*m1[1][0]*m0[0][8]-m2[2][4]*m1[0][8]*m0[1][0]-m2[2][4]*m1[0][6]*m0[1][3]-m2[2][4]*m1[0][3]*m0[1][6]-m2[2][4]*m1[0][0]*m0[1][8]+m2[2][3]*m1[1][8]*m0[0][1]+m2[2][3]*m1[1][7]*m0[0][3]+m2[2][3]*m1[1][6]*m0[0][4]+m2[2][3]*m1[1][4]*m0[0][6]+m2[2][3]*m1[1][3]*m0[0][7]+m2[2][3]*m1[1][1]*m0[0][8]-m2[2][3]*m1[0][8]*m0[1][1]-m2[2][3]*m1[0][7]*m0[1][3]-m2[2][3]*m1[0][6]*m0[1][4]-m2[2][3]*m1[0][4]*m0[1][6]-m2[2][3]*m1[0][3]*m0[1][7]-m2[2][3]*m1[0][1]*m0[1][8]+m2[2][1]*m1[1][8]*m0[0][3]+m2[2][1]*m1[1][6]*m0[0][5]+m2[2][1]*m1[1][5]*m0[0][6]+m2[2][1]*m1[1][3]*m0[0][8]-m2[2][1]*m1[0][8]*m0[1][3]-m2[2][1]*m1[0][6]*m0[1][5]-m2[2][1]*m1[0][5]*m0[1][6]-m2[2][1]*m1[0][3]*m0[1][8]+m2[2][0]*m1[1][8]*m0[0][4]+m2[2][0]*m1[1][7]*m0[0][5]+m2[2][0]*m1[1][5]*m0[0][7]+m2[2][0]*m1[1][4]*m0[0][8]-m2[2][0]*m1[0][8]*m0[1][4]-m2[2][0]*m1[0][7]*m0[1][5]-m2[2][0]*m1[0][5]*m0[1][7]-m2[2][0]*m1[0][4]*m0[1][8]-m2[1][8]*m1[2][4]*m0[0][0]-m2[1][8]*m1[2][3]*m0[0][1]-m2[1][8]*m1[2][1]*m0[0][3]-m2[1][8]*m1[2][0]*m0[0][4]+m2[1][8]*m1[0][4]*m0[2][0]+m2[1][8]*m1[0][3]*m0[2][1]+m2[1][8]*m1[0][1]*m0[2][3]+m2[1][8]*m1[0][0]*m0[2][4]-m2[1][7]*m1[2][5]*m0[0][0]-m2[1][7]*m1[2][3]*m0[0][3]-m2[1][7]*m1[2][0]*m0[0][5]+m2[1][7]*m1[0][5]*m0[2][0]+m2[1][7]*m1[0][3]*m0[2][3]+m2[1][7]*m1[0][0]*m0[2][5]-m2[1][6]*m1[2][5]*m0[0][1]-m2[1][6]*m1[2][4]*m0[0][3]-m2[1][6]*m1[2][3]*m0[0][4]-m2[1][6]*m1[2][1]*m0[0][5]+m2[1][6]*m1[0][5]*m0[2][1]+m2[1][6]*m1[0][4]*m0[2][3]+m2[1][6]*m1[0][3]*m0[2][4]+m2[1][6]*m1[0][1]*m0[2][5]-m2[1][5]*m1[2][7]*m0[0][0]-m2[1][5]*m1[2][6]*m0[0][1]-m2[1][5]*m1[2][1]*m0[0][6]-m2[1][5]*m1[2][0]*m0[0][7]+m2[1][5]*m1[0][7]*m0[2][0]+m2[1][5]*m1[0][6]*m0[2][1]+m2[1][5]*m1[0][1]*m0[2][6]+m2[1][5]*m1[0][0]*m0[2][7]-m2[1][4]*m1[2][8]*m0[0][0]-m2[1][4]*m1[2][6]*m0[0][3]-m2[1][4]*m1[2][3]*m0[0][6]-m2[1][4]*m1[2][0]*m0[0][8]+m2[1][4]*m1[0][8]*m0[2][0]+m2[1][4]*m1[0][6]*m0[2][3]+m2[1][4]*m1[0][3]*m0[2][6]+m2[1][4]*m1[0][0]*m0[2][8]-m2[1][3]*m1[2][8]*m0[0][1]-m2[1][3]*m1[2][7]*m0[0][3]-m2[1][3]*m1[2][6]*m0[0][4]-m2[1][3]*m1[2][4]*m0[0][6]-m2[1][3]*m1[2][3]*m0[0][7]-m2[1][3]*m1[2][1]*m0[0][8]+m2[1][3]*m1[0][8]*m0[2][1]+m2[1][3]*m1[0][7]*m0[2][3]+m2[1][3]*m1[0][6]*m0[2][4]+m2[1][3]*m1[0][4]*m0[2][6]+m2[1][3]*m1[0][3]*m0[2][7]+m2[1][3]*m1[0][1]*m0[2][8]-m2[1][1]*m1[2][8]*m0[0][3]-m2[1][1]*m1[2][6]*m0[0][5]-m2[1][1]*m1[2][5]*m0[0][6]-m2[1][1]*m1[2][3]*m0[0][8]+m2[1][1]*m1[0][8]*m0[2][3]+m2[1][1]*m1[0][6]*m0[2][5]+m2[1][1]*m1[0][5]*m0[2][6]+m2[1][1]*m1[0][3]*m0[2][8]-m2[1][0]*m1[2][8]*m0[0][4]-m2[1][0]*m1[2][7]*m0[0][5]-m2[1][0]*m1[2][5]*m0[0][7]-m2[1][0]*m1[2][4]*m0[0][8]+m2[1][0]*m1[0][8]*m0[2][4]+m2[1][0]*m1[0][7]*m0[2][5]+m2[1][0]*m1[0][5]*m0[2][7]+m2[1][0]*m1[0][4]*m0[2][8]+m2[0][8]*m1[2][4]*m0[1][0]+m2[0][8]*m1[2][3]*m0[1][1]+m2[0][8]*m1[2][1]*m0[1][3]+m2[0][8]*m1[2][0]*m0[1][4]-m2[0][8]*m1[1][4]*m0[2][0]-m2[0][8]*m1[1][3]*m0[2][1]-m2[0][8]*m1[1][1]*m0[2][3]-m2[0][8]*m1[1][0]*m0[2][4]+m2[0][7]*m1[2][5]*m0[1][0]+m2[0][7]*m1[2][3]*m0[1][3]+m2[0][7]*m1[2][0]*m0[1][5]-m2[0][7]*m1[1][5]*m0[2][0]-m2[0][7]*m1[1][3]*m0[2][3]-m2[0][7]*m1[1][0]*m0[2][5]+m2[0][6]*m1[2][5]*m0[1][1]+m2[0][6]*m1[2][4]*m0[1][3]+m2[0][6]*m1[2][3]*m0[1][4]+m2[0][6]*m1[2][1]*m0[1][5]-m2[0][6]*m1[1][5]*m0[2][1]-m2[0][6]*m1[1][4]*m0[2][3]-m2[0][6]*m1[1][3]*m0[2][4]-m2[0][6]*m1[1][1]*m0[2][5]+m2[0][5]*m1[2][7]*m0[1][0]+m2[0][5]*m1[2][6]*m0[1][1]+m2[0][5]*m1[2][1]*m0[1][6]+m2[0][5]*m1[2][0]*m0[1][7]-m2[0][5]*m1[1][7]*m0[2][0]-m2[0][5]*m1[1][6]*m0[2][1]-m2[0][5]*m1[1][1]*m0[2][6]-m2[0][5]*m1[1][0]*m0[2][7]+m2[0][4]*m1[2][8]*m0[1][0]+m2[0][4]*m1[2][6]*m0[1][3]+m2[0][4]*m1[2][3]*m0[1][6]+m2[0][4]*m1[2][0]*m0[1][8]-m2[0][4]*m1[1][8]*m0[2][0]-m2[0][4]*m1[1][6]*m0[2][3]-m2[0][4]*m1[1][3]*m0[2][6]-m2[0][4]*m1[1][0]*m0[2][8]+m2[0][3]*m1[2][8]*m0[1][1]+m2[0][3]*m1[2][7]*m0[1][3]+m2[0][3]*m1[2][6]*m0[1][4]+m2[0][3]*m1[2][4]*m0[1][6]+m2[0][3]*m1[2][3]*m0[1][7]+m2[0][3]*m1[2][1]*m0[1][8]-m2[0][3]*m1[1][8]*m0[2][1]-m2[0][3]*m1[1][7]*m0[2][3]-m2[0][3]*m1[1][6]*m0[2][4]-m2[0][3]*m1[1][4]*m0[2][6]-m2[0][3]*m1[1][3]*m0[2][7]-m2[0][3]*m1[1][1]*m0[2][8]+m2[0][1]*m1[2][8]*m0[1][3]+m2[0][1]*m1[2][6]*m0[1][5]+m2[0][1]*m1[2][5]*m0[1][6]+m2[0][1]*m1[2][3]*m0[1][8]-m2[0][1]*m1[1][8]*m0[2][3]-m2[0][1]*m1[1][6]*m0[2][5]-m2[0][1]*m1[1][5]*m0[2][6]-m2[0][1]*m1[1][3]*m0[2][8]+m2[0][0]*m1[2][8]*m0[1][4]+m2[0][0]*m1[2][7]*m0[1][5]+m2[0][0]*m1[2][5]*m0[1][7]+m2[0][0]*m1[2][4]*m0[1][8]-m2[0][0]*m1[1][8]*m0[2][4]-m2[0][0]*m1[1][7]*m0[2][5]-m2[0][0]*m1[1][5]*m0[2][7]-m2[0][0]*m1[1][4]*m0[2][8]; M1(row,41) = m2[2][8]*m1[1][4]*m0[0][1]+m2[2][8]*m1[1][3]*m0[0][2]+m2[2][8]*m1[1][2]*m0[0][3]+m2[2][8]*m1[1][1]*m0[0][4]-m2[2][8]*m1[0][4]*m0[1][1]-m2[2][8]*m1[0][3]*m0[1][2]-m2[2][8]*m1[0][2]*m0[1][3]-m2[2][8]*m1[0][1]*m0[1][4]+m2[2][7]*m1[1][5]*m0[0][1]+m2[2][7]*m1[1][4]*m0[0][3]+m2[2][7]*m1[1][3]*m0[0][4]+m2[2][7]*m1[1][1]*m0[0][5]-m2[2][7]*m1[0][5]*m0[1][1]-m2[2][7]*m1[0][4]*m0[1][3]-m2[2][7]*m1[0][3]*m0[1][4]-m2[2][7]*m1[0][1]*m0[1][5]+m2[2][6]*m1[1][5]*m0[0][2]+m2[2][6]*m1[1][4]*m0[0][4]+m2[2][6]*m1[1][2]*m0[0][5]-m2[2][6]*m1[0][5]*m0[1][2]-m2[2][6]*m1[0][4]*m0[1][4]-m2[2][6]*m1[0][2]*m0[1][5]+m2[2][5]*m1[1][7]*m0[0][1]+m2[2][5]*m1[1][6]*m0[0][2]+m2[2][5]*m1[1][2]*m0[0][6]+m2[2][5]*m1[1][1]*m0[0][7]-m2[2][5]*m1[0][7]*m0[1][1]-m2[2][5]*m1[0][6]*m0[1][2]-m2[2][5]*m1[0][2]*m0[1][6]-m2[2][5]*m1[0][1]*m0[1][7]+m2[2][4]*m1[1][8]*m0[0][1]+m2[2][4]*m1[1][7]*m0[0][3]+m2[2][4]*m1[1][6]*m0[0][4]+m2[2][4]*m1[1][4]*m0[0][6]+m2[2][4]*m1[1][3]*m0[0][7]+m2[2][4]*m1[1][1]*m0[0][8]-m2[2][4]*m1[0][8]*m0[1][1]-m2[2][4]*m1[0][7]*m0[1][3]-m2[2][4]*m1[0][6]*m0[1][4]-m2[2][4]*m1[0][4]*m0[1][6]-m2[2][4]*m1[0][3]*m0[1][7]-m2[2][4]*m1[0][1]*m0[1][8]+m2[2][3]*m1[1][8]*m0[0][2]+m2[2][3]*m1[1][7]*m0[0][4]+m2[2][3]*m1[1][4]*m0[0][7]+m2[2][3]*m1[1][2]*m0[0][8]-m2[2][3]*m1[0][8]*m0[1][2]-m2[2][3]*m1[0][7]*m0[1][4]-m2[2][3]*m1[0][4]*m0[1][7]-m2[2][3]*m1[0][2]*m0[1][8]+m2[2][2]*m1[1][8]*m0[0][3]+m2[2][2]*m1[1][6]*m0[0][5]+m2[2][2]*m1[1][5]*m0[0][6]+m2[2][2]*m1[1][3]*m0[0][8]-m2[2][2]*m1[0][8]*m0[1][3]-m2[2][2]*m1[0][6]*m0[1][5]-m2[2][2]*m1[0][5]*m0[1][6]-m2[2][2]*m1[0][3]*m0[1][8]+m2[2][1]*m1[1][8]*m0[0][4]+m2[2][1]*m1[1][7]*m0[0][5]+m2[2][1]*m1[1][5]*m0[0][7]+m2[2][1]*m1[1][4]*m0[0][8]-m2[2][1]*m1[0][8]*m0[1][4]-m2[2][1]*m1[0][7]*m0[1][5]-m2[2][1]*m1[0][5]*m0[1][7]-m2[2][1]*m1[0][4]*m0[1][8]-m2[1][8]*m1[2][4]*m0[0][1]-m2[1][8]*m1[2][3]*m0[0][2]-m2[1][8]*m1[2][2]*m0[0][3]-m2[1][8]*m1[2][1]*m0[0][4]+m2[1][8]*m1[0][4]*m0[2][1]+m2[1][8]*m1[0][3]*m0[2][2]+m2[1][8]*m1[0][2]*m0[2][3]+m2[1][8]*m1[0][1]*m0[2][4]-m2[1][7]*m1[2][5]*m0[0][1]-m2[1][7]*m1[2][4]*m0[0][3]-m2[1][7]*m1[2][3]*m0[0][4]-m2[1][7]*m1[2][1]*m0[0][5]+m2[1][7]*m1[0][5]*m0[2][1]+m2[1][7]*m1[0][4]*m0[2][3]+m2[1][7]*m1[0][3]*m0[2][4]+m2[1][7]*m1[0][1]*m0[2][5]-m2[1][6]*m1[2][5]*m0[0][2]-m2[1][6]*m1[2][4]*m0[0][4]-m2[1][6]*m1[2][2]*m0[0][5]+m2[1][6]*m1[0][5]*m0[2][2]+m2[1][6]*m1[0][4]*m0[2][4]+m2[1][6]*m1[0][2]*m0[2][5]-m2[1][5]*m1[2][7]*m0[0][1]-m2[1][5]*m1[2][6]*m0[0][2]-m2[1][5]*m1[2][2]*m0[0][6]-m2[1][5]*m1[2][1]*m0[0][7]+m2[1][5]*m1[0][7]*m0[2][1]+m2[1][5]*m1[0][6]*m0[2][2]+m2[1][5]*m1[0][2]*m0[2][6]+m2[1][5]*m1[0][1]*m0[2][7]-m2[1][4]*m1[2][8]*m0[0][1]-m2[1][4]*m1[2][7]*m0[0][3]-m2[1][4]*m1[2][6]*m0[0][4]-m2[1][4]*m1[2][4]*m0[0][6]-m2[1][4]*m1[2][3]*m0[0][7]-m2[1][4]*m1[2][1]*m0[0][8]+m2[1][4]*m1[0][8]*m0[2][1]+m2[1][4]*m1[0][7]*m0[2][3]+m2[1][4]*m1[0][6]*m0[2][4]+m2[1][4]*m1[0][4]*m0[2][6]+m2[1][4]*m1[0][3]*m0[2][7]+m2[1][4]*m1[0][1]*m0[2][8]-m2[1][3]*m1[2][8]*m0[0][2]-m2[1][3]*m1[2][7]*m0[0][4]-m2[1][3]*m1[2][4]*m0[0][7]-m2[1][3]*m1[2][2]*m0[0][8]+m2[1][3]*m1[0][8]*m0[2][2]+m2[1][3]*m1[0][7]*m0[2][4]+m2[1][3]*m1[0][4]*m0[2][7]+m2[1][3]*m1[0][2]*m0[2][8]-m2[1][2]*m1[2][8]*m0[0][3]-m2[1][2]*m1[2][6]*m0[0][5]-m2[1][2]*m1[2][5]*m0[0][6]-m2[1][2]*m1[2][3]*m0[0][8]+m2[1][2]*m1[0][8]*m0[2][3]+m2[1][2]*m1[0][6]*m0[2][5]+m2[1][2]*m1[0][5]*m0[2][6]+m2[1][2]*m1[0][3]*m0[2][8]-m2[1][1]*m1[2][8]*m0[0][4]-m2[1][1]*m1[2][7]*m0[0][5]-m2[1][1]*m1[2][5]*m0[0][7]-m2[1][1]*m1[2][4]*m0[0][8]+m2[1][1]*m1[0][8]*m0[2][4]+m2[1][1]*m1[0][7]*m0[2][5]+m2[1][1]*m1[0][5]*m0[2][7]+m2[1][1]*m1[0][4]*m0[2][8]+m2[0][8]*m1[2][4]*m0[1][1]+m2[0][8]*m1[2][3]*m0[1][2]+m2[0][8]*m1[2][2]*m0[1][3]+m2[0][8]*m1[2][1]*m0[1][4]-m2[0][8]*m1[1][4]*m0[2][1]-m2[0][8]*m1[1][3]*m0[2][2]-m2[0][8]*m1[1][2]*m0[2][3]-m2[0][8]*m1[1][1]*m0[2][4]+m2[0][7]*m1[2][5]*m0[1][1]+m2[0][7]*m1[2][4]*m0[1][3]+m2[0][7]*m1[2][3]*m0[1][4]+m2[0][7]*m1[2][1]*m0[1][5]-m2[0][7]*m1[1][5]*m0[2][1]-m2[0][7]*m1[1][4]*m0[2][3]-m2[0][7]*m1[1][3]*m0[2][4]-m2[0][7]*m1[1][1]*m0[2][5]+m2[0][6]*m1[2][5]*m0[1][2]+m2[0][6]*m1[2][4]*m0[1][4]+m2[0][6]*m1[2][2]*m0[1][5]-m2[0][6]*m1[1][5]*m0[2][2]-m2[0][6]*m1[1][4]*m0[2][4]-m2[0][6]*m1[1][2]*m0[2][5]+m2[0][5]*m1[2][7]*m0[1][1]+m2[0][5]*m1[2][6]*m0[1][2]+m2[0][5]*m1[2][2]*m0[1][6]+m2[0][5]*m1[2][1]*m0[1][7]-m2[0][5]*m1[1][7]*m0[2][1]-m2[0][5]*m1[1][6]*m0[2][2]-m2[0][5]*m1[1][2]*m0[2][6]-m2[0][5]*m1[1][1]*m0[2][7]+m2[0][4]*m1[2][8]*m0[1][1]+m2[0][4]*m1[2][7]*m0[1][3]+m2[0][4]*m1[2][6]*m0[1][4]+m2[0][4]*m1[2][4]*m0[1][6]+m2[0][4]*m1[2][3]*m0[1][7]+m2[0][4]*m1[2][1]*m0[1][8]-m2[0][4]*m1[1][8]*m0[2][1]-m2[0][4]*m1[1][7]*m0[2][3]-m2[0][4]*m1[1][6]*m0[2][4]-m2[0][4]*m1[1][4]*m0[2][6]-m2[0][4]*m1[1][3]*m0[2][7]-m2[0][4]*m1[1][1]*m0[2][8]+m2[0][3]*m1[2][8]*m0[1][2]+m2[0][3]*m1[2][7]*m0[1][4]+m2[0][3]*m1[2][4]*m0[1][7]+m2[0][3]*m1[2][2]*m0[1][8]-m2[0][3]*m1[1][8]*m0[2][2]-m2[0][3]*m1[1][7]*m0[2][4]-m2[0][3]*m1[1][4]*m0[2][7]-m2[0][3]*m1[1][2]*m0[2][8]+m2[0][2]*m1[2][8]*m0[1][3]+m2[0][2]*m1[2][6]*m0[1][5]+m2[0][2]*m1[2][5]*m0[1][6]+m2[0][2]*m1[2][3]*m0[1][8]-m2[0][2]*m1[1][8]*m0[2][3]-m2[0][2]*m1[1][6]*m0[2][5]-m2[0][2]*m1[1][5]*m0[2][6]-m2[0][2]*m1[1][3]*m0[2][8]+m2[0][1]*m1[2][8]*m0[1][4]+m2[0][1]*m1[2][7]*m0[1][5]+m2[0][1]*m1[2][5]*m0[1][7]+m2[0][1]*m1[2][4]*m0[1][8]-m2[0][1]*m1[1][8]*m0[2][4]-m2[0][1]*m1[1][7]*m0[2][5]-m2[0][1]*m1[1][5]*m0[2][7]-m2[0][1]*m1[1][4]*m0[2][8]; M1(row,42) = m2[2][8]*m1[1][4]*m0[0][2]+m2[2][8]*m1[1][2]*m0[0][4]-m2[2][8]*m1[0][4]*m0[1][2]-m2[2][8]*m1[0][2]*m0[1][4]+m2[2][7]*m1[1][5]*m0[0][2]+m2[2][7]*m1[1][4]*m0[0][4]+m2[2][7]*m1[1][2]*m0[0][5]-m2[2][7]*m1[0][5]*m0[1][2]-m2[2][7]*m1[0][4]*m0[1][4]-m2[2][7]*m1[0][2]*m0[1][5]+m2[2][5]*m1[1][7]*m0[0][2]+m2[2][5]*m1[1][2]*m0[0][7]-m2[2][5]*m1[0][7]*m0[1][2]-m2[2][5]*m1[0][2]*m0[1][7]+m2[2][4]*m1[1][8]*m0[0][2]+m2[2][4]*m1[1][7]*m0[0][4]+m2[2][4]*m1[1][4]*m0[0][7]+m2[2][4]*m1[1][2]*m0[0][8]-m2[2][4]*m1[0][8]*m0[1][2]-m2[2][4]*m1[0][7]*m0[1][4]-m2[2][4]*m1[0][4]*m0[1][7]-m2[2][4]*m1[0][2]*m0[1][8]+m2[2][2]*m1[1][8]*m0[0][4]+m2[2][2]*m1[1][7]*m0[0][5]+m2[2][2]*m1[1][5]*m0[0][7]+m2[2][2]*m1[1][4]*m0[0][8]-m2[2][2]*m1[0][8]*m0[1][4]-m2[2][2]*m1[0][7]*m0[1][5]-m2[2][2]*m1[0][5]*m0[1][7]-m2[2][2]*m1[0][4]*m0[1][8]-m2[1][8]*m1[2][4]*m0[0][2]-m2[1][8]*m1[2][2]*m0[0][4]+m2[1][8]*m1[0][4]*m0[2][2]+m2[1][8]*m1[0][2]*m0[2][4]-m2[1][7]*m1[2][5]*m0[0][2]-m2[1][7]*m1[2][4]*m0[0][4]-m2[1][7]*m1[2][2]*m0[0][5]+m2[1][7]*m1[0][5]*m0[2][2]+m2[1][7]*m1[0][4]*m0[2][4]+m2[1][7]*m1[0][2]*m0[2][5]-m2[1][5]*m1[2][7]*m0[0][2]-m2[1][5]*m1[2][2]*m0[0][7]+m2[1][5]*m1[0][7]*m0[2][2]+m2[1][5]*m1[0][2]*m0[2][7]-m2[1][4]*m1[2][8]*m0[0][2]-m2[1][4]*m1[2][7]*m0[0][4]-m2[1][4]*m1[2][4]*m0[0][7]-m2[1][4]*m1[2][2]*m0[0][8]+m2[1][4]*m1[0][8]*m0[2][2]+m2[1][4]*m1[0][7]*m0[2][4]+m2[1][4]*m1[0][4]*m0[2][7]+m2[1][4]*m1[0][2]*m0[2][8]-m2[1][2]*m1[2][8]*m0[0][4]-m2[1][2]*m1[2][7]*m0[0][5]-m2[1][2]*m1[2][5]*m0[0][7]-m2[1][2]*m1[2][4]*m0[0][8]+m2[1][2]*m1[0][8]*m0[2][4]+m2[1][2]*m1[0][7]*m0[2][5]+m2[1][2]*m1[0][5]*m0[2][7]+m2[1][2]*m1[0][4]*m0[2][8]+m2[0][8]*m1[2][4]*m0[1][2]+m2[0][8]*m1[2][2]*m0[1][4]-m2[0][8]*m1[1][4]*m0[2][2]-m2[0][8]*m1[1][2]*m0[2][4]+m2[0][7]*m1[2][5]*m0[1][2]+m2[0][7]*m1[2][4]*m0[1][4]+m2[0][7]*m1[2][2]*m0[1][5]-m2[0][7]*m1[1][5]*m0[2][2]-m2[0][7]*m1[1][4]*m0[2][4]-m2[0][7]*m1[1][2]*m0[2][5]+m2[0][5]*m1[2][7]*m0[1][2]+m2[0][5]*m1[2][2]*m0[1][7]-m2[0][5]*m1[1][7]*m0[2][2]-m2[0][5]*m1[1][2]*m0[2][7]+m2[0][4]*m1[2][8]*m0[1][2]+m2[0][4]*m1[2][7]*m0[1][4]+m2[0][4]*m1[2][4]*m0[1][7]+m2[0][4]*m1[2][2]*m0[1][8]-m2[0][4]*m1[1][8]*m0[2][2]-m2[0][4]*m1[1][7]*m0[2][4]-m2[0][4]*m1[1][4]*m0[2][7]-m2[0][4]*m1[1][2]*m0[2][8]+m2[0][2]*m1[2][8]*m0[1][4]+m2[0][2]*m1[2][7]*m0[1][5]+m2[0][2]*m1[2][5]*m0[1][7]+m2[0][2]*m1[2][4]*m0[1][8]-m2[0][2]*m1[1][8]*m0[2][4]-m2[0][2]*m1[1][7]*m0[2][5]-m2[0][2]*m1[1][5]*m0[2][7]-m2[0][2]*m1[1][4]*m0[2][8]; M1(row,43) = m2[2][8]*m1[1][5]*m0[0][0]+m2[2][8]*m1[1][3]*m0[0][3]+m2[2][8]*m1[1][0]*m0[0][5]-m2[2][8]*m1[0][5]*m0[1][0]-m2[2][8]*m1[0][3]*m0[1][3]-m2[2][8]*m1[0][0]*m0[1][5]+m2[2][6]*m1[1][5]*m0[0][3]+m2[2][6]*m1[1][3]*m0[0][5]-m2[2][6]*m1[0][5]*m0[1][3]-m2[2][6]*m1[0][3]*m0[1][5]+m2[2][5]*m1[1][8]*m0[0][0]+m2[2][5]*m1[1][6]*m0[0][3]+m2[2][5]*m1[1][3]*m0[0][6]+m2[2][5]*m1[1][0]*m0[0][8]-m2[2][5]*m1[0][8]*m0[1][0]-m2[2][5]*m1[0][6]*m0[1][3]-m2[2][5]*m1[0][3]*m0[1][6]-m2[2][5]*m1[0][0]*m0[1][8]+m2[2][3]*m1[1][8]*m0[0][3]+m2[2][3]*m1[1][6]*m0[0][5]+m2[2][3]*m1[1][5]*m0[0][6]+m2[2][3]*m1[1][3]*m0[0][8]-m2[2][3]*m1[0][8]*m0[1][3]-m2[2][3]*m1[0][6]*m0[1][5]-m2[2][3]*m1[0][5]*m0[1][6]-m2[2][3]*m1[0][3]*m0[1][8]+m2[2][0]*m1[1][8]*m0[0][5]+m2[2][0]*m1[1][5]*m0[0][8]-m2[2][0]*m1[0][8]*m0[1][5]-m2[2][0]*m1[0][5]*m0[1][8]-m2[1][8]*m1[2][5]*m0[0][0]-m2[1][8]*m1[2][3]*m0[0][3]-m2[1][8]*m1[2][0]*m0[0][5]+m2[1][8]*m1[0][5]*m0[2][0]+m2[1][8]*m1[0][3]*m0[2][3]+m2[1][8]*m1[0][0]*m0[2][5]-m2[1][6]*m1[2][5]*m0[0][3]-m2[1][6]*m1[2][3]*m0[0][5]+m2[1][6]*m1[0][5]*m0[2][3]+m2[1][6]*m1[0][3]*m0[2][5]-m2[1][5]*m1[2][8]*m0[0][0]-m2[1][5]*m1[2][6]*m0[0][3]-m2[1][5]*m1[2][3]*m0[0][6]-m2[1][5]*m1[2][0]*m0[0][8]+m2[1][5]*m1[0][8]*m0[2][0]+m2[1][5]*m1[0][6]*m0[2][3]+m2[1][5]*m1[0][3]*m0[2][6]+m2[1][5]*m1[0][0]*m0[2][8]-m2[1][3]*m1[2][8]*m0[0][3]-m2[1][3]*m1[2][6]*m0[0][5]-m2[1][3]*m1[2][5]*m0[0][6]-m2[1][3]*m1[2][3]*m0[0][8]+m2[1][3]*m1[0][8]*m0[2][3]+m2[1][3]*m1[0][6]*m0[2][5]+m2[1][3]*m1[0][5]*m0[2][6]+m2[1][3]*m1[0][3]*m0[2][8]-m2[1][0]*m1[2][8]*m0[0][5]-m2[1][0]*m1[2][5]*m0[0][8]+m2[1][0]*m1[0][8]*m0[2][5]+m2[1][0]*m1[0][5]*m0[2][8]+m2[0][8]*m1[2][5]*m0[1][0]+m2[0][8]*m1[2][3]*m0[1][3]+m2[0][8]*m1[2][0]*m0[1][5]-m2[0][8]*m1[1][5]*m0[2][0]-m2[0][8]*m1[1][3]*m0[2][3]-m2[0][8]*m1[1][0]*m0[2][5]+m2[0][6]*m1[2][5]*m0[1][3]+m2[0][6]*m1[2][3]*m0[1][5]-m2[0][6]*m1[1][5]*m0[2][3]-m2[0][6]*m1[1][3]*m0[2][5]+m2[0][5]*m1[2][8]*m0[1][0]+m2[0][5]*m1[2][6]*m0[1][3]+m2[0][5]*m1[2][3]*m0[1][6]+m2[0][5]*m1[2][0]*m0[1][8]-m2[0][5]*m1[1][8]*m0[2][0]-m2[0][5]*m1[1][6]*m0[2][3]-m2[0][5]*m1[1][3]*m0[2][6]-m2[0][5]*m1[1][0]*m0[2][8]+m2[0][3]*m1[2][8]*m0[1][3]+m2[0][3]*m1[2][6]*m0[1][5]+m2[0][3]*m1[2][5]*m0[1][6]+m2[0][3]*m1[2][3]*m0[1][8]-m2[0][3]*m1[1][8]*m0[2][3]-m2[0][3]*m1[1][6]*m0[2][5]-m2[0][3]*m1[1][5]*m0[2][6]-m2[0][3]*m1[1][3]*m0[2][8]+m2[0][0]*m1[2][8]*m0[1][5]+m2[0][0]*m1[2][5]*m0[1][8]-m2[0][0]*m1[1][8]*m0[2][5]-m2[0][0]*m1[1][5]*m0[2][8]; M1(row,44) = m2[2][8]*m1[1][5]*m0[0][1]+m2[2][8]*m1[1][4]*m0[0][3]+m2[2][8]*m1[1][3]*m0[0][4]+m2[2][8]*m1[1][1]*m0[0][5]-m2[2][8]*m1[0][5]*m0[1][1]-m2[2][8]*m1[0][4]*m0[1][3]-m2[2][8]*m1[0][3]*m0[1][4]-m2[2][8]*m1[0][1]*m0[1][5]+m2[2][7]*m1[1][5]*m0[0][3]+m2[2][7]*m1[1][3]*m0[0][5]-m2[2][7]*m1[0][5]*m0[1][3]-m2[2][7]*m1[0][3]*m0[1][5]+m2[2][6]*m1[1][5]*m0[0][4]+m2[2][6]*m1[1][4]*m0[0][5]-m2[2][6]*m1[0][5]*m0[1][4]-m2[2][6]*m1[0][4]*m0[1][5]+m2[2][5]*m1[1][8]*m0[0][1]+m2[2][5]*m1[1][7]*m0[0][3]+m2[2][5]*m1[1][6]*m0[0][4]+m2[2][5]*m1[1][4]*m0[0][6]+m2[2][5]*m1[1][3]*m0[0][7]+m2[2][5]*m1[1][1]*m0[0][8]-m2[2][5]*m1[0][8]*m0[1][1]-m2[2][5]*m1[0][7]*m0[1][3]-m2[2][5]*m1[0][6]*m0[1][4]-m2[2][5]*m1[0][4]*m0[1][6]-m2[2][5]*m1[0][3]*m0[1][7]-m2[2][5]*m1[0][1]*m0[1][8]+m2[2][4]*m1[1][8]*m0[0][3]+m2[2][4]*m1[1][6]*m0[0][5]+m2[2][4]*m1[1][5]*m0[0][6]+m2[2][4]*m1[1][3]*m0[0][8]-m2[2][4]*m1[0][8]*m0[1][3]-m2[2][4]*m1[0][6]*m0[1][5]-m2[2][4]*m1[0][5]*m0[1][6]-m2[2][4]*m1[0][3]*m0[1][8]+m2[2][3]*m1[1][8]*m0[0][4]+m2[2][3]*m1[1][7]*m0[0][5]+m2[2][3]*m1[1][5]*m0[0][7]+m2[2][3]*m1[1][4]*m0[0][8]-m2[2][3]*m1[0][8]*m0[1][4]-m2[2][3]*m1[0][7]*m0[1][5]-m2[2][3]*m1[0][5]*m0[1][7]-m2[2][3]*m1[0][4]*m0[1][8]+m2[2][1]*m1[1][8]*m0[0][5]+m2[2][1]*m1[1][5]*m0[0][8]-m2[2][1]*m1[0][8]*m0[1][5]-m2[2][1]*m1[0][5]*m0[1][8]-m2[1][8]*m1[2][5]*m0[0][1]-m2[1][8]*m1[2][4]*m0[0][3]-m2[1][8]*m1[2][3]*m0[0][4]-m2[1][8]*m1[2][1]*m0[0][5]+m2[1][8]*m1[0][5]*m0[2][1]+m2[1][8]*m1[0][4]*m0[2][3]+m2[1][8]*m1[0][3]*m0[2][4]+m2[1][8]*m1[0][1]*m0[2][5]-m2[1][7]*m1[2][5]*m0[0][3]-m2[1][7]*m1[2][3]*m0[0][5]+m2[1][7]*m1[0][5]*m0[2][3]+m2[1][7]*m1[0][3]*m0[2][5]-m2[1][6]*m1[2][5]*m0[0][4]-m2[1][6]*m1[2][4]*m0[0][5]+m2[1][6]*m1[0][5]*m0[2][4]+m2[1][6]*m1[0][4]*m0[2][5]-m2[1][5]*m1[2][8]*m0[0][1]-m2[1][5]*m1[2][7]*m0[0][3]-m2[1][5]*m1[2][6]*m0[0][4]-m2[1][5]*m1[2][4]*m0[0][6]-m2[1][5]*m1[2][3]*m0[0][7]-m2[1][5]*m1[2][1]*m0[0][8]+m2[1][5]*m1[0][8]*m0[2][1]+m2[1][5]*m1[0][7]*m0[2][3]+m2[1][5]*m1[0][6]*m0[2][4]+m2[1][5]*m1[0][4]*m0[2][6]+m2[1][5]*m1[0][3]*m0[2][7]+m2[1][5]*m1[0][1]*m0[2][8]-m2[1][4]*m1[2][8]*m0[0][3]-m2[1][4]*m1[2][6]*m0[0][5]-m2[1][4]*m1[2][5]*m0[0][6]-m2[1][4]*m1[2][3]*m0[0][8]+m2[1][4]*m1[0][8]*m0[2][3]+m2[1][4]*m1[0][6]*m0[2][5]+m2[1][4]*m1[0][5]*m0[2][6]+m2[1][4]*m1[0][3]*m0[2][8]-m2[1][3]*m1[2][8]*m0[0][4]-m2[1][3]*m1[2][7]*m0[0][5]-m2[1][3]*m1[2][5]*m0[0][7]-m2[1][3]*m1[2][4]*m0[0][8]+m2[1][3]*m1[0][8]*m0[2][4]+m2[1][3]*m1[0][7]*m0[2][5]+m2[1][3]*m1[0][5]*m0[2][7]+m2[1][3]*m1[0][4]*m0[2][8]-m2[1][1]*m1[2][8]*m0[0][5]-m2[1][1]*m1[2][5]*m0[0][8]+m2[1][1]*m1[0][8]*m0[2][5]+m2[1][1]*m1[0][5]*m0[2][8]+m2[0][8]*m1[2][5]*m0[1][1]+m2[0][8]*m1[2][4]*m0[1][3]+m2[0][8]*m1[2][3]*m0[1][4]+m2[0][8]*m1[2][1]*m0[1][5]-m2[0][8]*m1[1][5]*m0[2][1]-m2[0][8]*m1[1][4]*m0[2][3]-m2[0][8]*m1[1][3]*m0[2][4]-m2[0][8]*m1[1][1]*m0[2][5]+m2[0][7]*m1[2][5]*m0[1][3]+m2[0][7]*m1[2][3]*m0[1][5]-m2[0][7]*m1[1][5]*m0[2][3]-m2[0][7]*m1[1][3]*m0[2][5]+m2[0][6]*m1[2][5]*m0[1][4]+m2[0][6]*m1[2][4]*m0[1][5]-m2[0][6]*m1[1][5]*m0[2][4]-m2[0][6]*m1[1][4]*m0[2][5]+m2[0][5]*m1[2][8]*m0[1][1]+m2[0][5]*m1[2][7]*m0[1][3]+m2[0][5]*m1[2][6]*m0[1][4]+m2[0][5]*m1[2][4]*m0[1][6]+m2[0][5]*m1[2][3]*m0[1][7]+m2[0][5]*m1[2][1]*m0[1][8]-m2[0][5]*m1[1][8]*m0[2][1]-m2[0][5]*m1[1][7]*m0[2][3]-m2[0][5]*m1[1][6]*m0[2][4]-m2[0][5]*m1[1][4]*m0[2][6]-m2[0][5]*m1[1][3]*m0[2][7]-m2[0][5]*m1[1][1]*m0[2][8]+m2[0][4]*m1[2][8]*m0[1][3]+m2[0][4]*m1[2][6]*m0[1][5]+m2[0][4]*m1[2][5]*m0[1][6]+m2[0][4]*m1[2][3]*m0[1][8]-m2[0][4]*m1[1][8]*m0[2][3]-m2[0][4]*m1[1][6]*m0[2][5]-m2[0][4]*m1[1][5]*m0[2][6]-m2[0][4]*m1[1][3]*m0[2][8]+m2[0][3]*m1[2][8]*m0[1][4]+m2[0][3]*m1[2][7]*m0[1][5]+m2[0][3]*m1[2][5]*m0[1][7]+m2[0][3]*m1[2][4]*m0[1][8]-m2[0][3]*m1[1][8]*m0[2][4]-m2[0][3]*m1[1][7]*m0[2][5]-m2[0][3]*m1[1][5]*m0[2][7]-m2[0][3]*m1[1][4]*m0[2][8]+m2[0][1]*m1[2][8]*m0[1][5]+m2[0][1]*m1[2][5]*m0[1][8]-m2[0][1]*m1[1][8]*m0[2][5]-m2[0][1]*m1[1][5]*m0[2][8]; M1(row,45) = m2[2][8]*m1[1][5]*m0[0][2]+m2[2][8]*m1[1][4]*m0[0][4]+m2[2][8]*m1[1][2]*m0[0][5]-m2[2][8]*m1[0][5]*m0[1][2]-m2[2][8]*m1[0][4]*m0[1][4]-m2[2][8]*m1[0][2]*m0[1][5]+m2[2][7]*m1[1][5]*m0[0][4]+m2[2][7]*m1[1][4]*m0[0][5]-m2[2][7]*m1[0][5]*m0[1][4]-m2[2][7]*m1[0][4]*m0[1][5]+m2[2][5]*m1[1][8]*m0[0][2]+m2[2][5]*m1[1][7]*m0[0][4]+m2[2][5]*m1[1][4]*m0[0][7]+m2[2][5]*m1[1][2]*m0[0][8]-m2[2][5]*m1[0][8]*m0[1][2]-m2[2][5]*m1[0][7]*m0[1][4]-m2[2][5]*m1[0][4]*m0[1][7]-m2[2][5]*m1[0][2]*m0[1][8]+m2[2][4]*m1[1][8]*m0[0][4]+m2[2][4]*m1[1][7]*m0[0][5]+m2[2][4]*m1[1][5]*m0[0][7]+m2[2][4]*m1[1][4]*m0[0][8]-m2[2][4]*m1[0][8]*m0[1][4]-m2[2][4]*m1[0][7]*m0[1][5]-m2[2][4]*m1[0][5]*m0[1][7]-m2[2][4]*m1[0][4]*m0[1][8]+m2[2][2]*m1[1][8]*m0[0][5]+m2[2][2]*m1[1][5]*m0[0][8]-m2[2][2]*m1[0][8]*m0[1][5]-m2[2][2]*m1[0][5]*m0[1][8]-m2[1][8]*m1[2][5]*m0[0][2]-m2[1][8]*m1[2][4]*m0[0][4]-m2[1][8]*m1[2][2]*m0[0][5]+m2[1][8]*m1[0][5]*m0[2][2]+m2[1][8]*m1[0][4]*m0[2][4]+m2[1][8]*m1[0][2]*m0[2][5]-m2[1][7]*m1[2][5]*m0[0][4]-m2[1][7]*m1[2][4]*m0[0][5]+m2[1][7]*m1[0][5]*m0[2][4]+m2[1][7]*m1[0][4]*m0[2][5]-m2[1][5]*m1[2][8]*m0[0][2]-m2[1][5]*m1[2][7]*m0[0][4]-m2[1][5]*m1[2][4]*m0[0][7]-m2[1][5]*m1[2][2]*m0[0][8]+m2[1][5]*m1[0][8]*m0[2][2]+m2[1][5]*m1[0][7]*m0[2][4]+m2[1][5]*m1[0][4]*m0[2][7]+m2[1][5]*m1[0][2]*m0[2][8]-m2[1][4]*m1[2][8]*m0[0][4]-m2[1][4]*m1[2][7]*m0[0][5]-m2[1][4]*m1[2][5]*m0[0][7]-m2[1][4]*m1[2][4]*m0[0][8]+m2[1][4]*m1[0][8]*m0[2][4]+m2[1][4]*m1[0][7]*m0[2][5]+m2[1][4]*m1[0][5]*m0[2][7]+m2[1][4]*m1[0][4]*m0[2][8]-m2[1][2]*m1[2][8]*m0[0][5]-m2[1][2]*m1[2][5]*m0[0][8]+m2[1][2]*m1[0][8]*m0[2][5]+m2[1][2]*m1[0][5]*m0[2][8]+m2[0][8]*m1[2][5]*m0[1][2]+m2[0][8]*m1[2][4]*m0[1][4]+m2[0][8]*m1[2][2]*m0[1][5]-m2[0][8]*m1[1][5]*m0[2][2]-m2[0][8]*m1[1][4]*m0[2][4]-m2[0][8]*m1[1][2]*m0[2][5]+m2[0][7]*m1[2][5]*m0[1][4]+m2[0][7]*m1[2][4]*m0[1][5]-m2[0][7]*m1[1][5]*m0[2][4]-m2[0][7]*m1[1][4]*m0[2][5]+m2[0][5]*m1[2][8]*m0[1][2]+m2[0][5]*m1[2][7]*m0[1][4]+m2[0][5]*m1[2][4]*m0[1][7]+m2[0][5]*m1[2][2]*m0[1][8]-m2[0][5]*m1[1][8]*m0[2][2]-m2[0][5]*m1[1][7]*m0[2][4]-m2[0][5]*m1[1][4]*m0[2][7]-m2[0][5]*m1[1][2]*m0[2][8]+m2[0][4]*m1[2][8]*m0[1][4]+m2[0][4]*m1[2][7]*m0[1][5]+m2[0][4]*m1[2][5]*m0[1][7]+m2[0][4]*m1[2][4]*m0[1][8]-m2[0][4]*m1[1][8]*m0[2][4]-m2[0][4]*m1[1][7]*m0[2][5]-m2[0][4]*m1[1][5]*m0[2][7]-m2[0][4]*m1[1][4]*m0[2][8]+m2[0][2]*m1[2][8]*m0[1][5]+m2[0][2]*m1[2][5]*m0[1][8]-m2[0][2]*m1[1][8]*m0[2][5]-m2[0][2]*m1[1][5]*m0[2][8]; M1(row,46) = m2[2][8]*m1[1][5]*m0[0][3]+m2[2][8]*m1[1][3]*m0[0][5]-m2[2][8]*m1[0][5]*m0[1][3]-m2[2][8]*m1[0][3]*m0[1][5]+m2[2][6]*m1[1][5]*m0[0][5]-m2[2][6]*m1[0][5]*m0[1][5]+m2[2][5]*m1[1][8]*m0[0][3]+m2[2][5]*m1[1][6]*m0[0][5]+m2[2][5]*m1[1][5]*m0[0][6]+m2[2][5]*m1[1][3]*m0[0][8]-m2[2][5]*m1[0][8]*m0[1][3]-m2[2][5]*m1[0][6]*m0[1][5]-m2[2][5]*m1[0][5]*m0[1][6]-m2[2][5]*m1[0][3]*m0[1][8]+m2[2][3]*m1[1][8]*m0[0][5]+m2[2][3]*m1[1][5]*m0[0][8]-m2[2][3]*m1[0][8]*m0[1][5]-m2[2][3]*m1[0][5]*m0[1][8]-m2[1][8]*m1[2][5]*m0[0][3]-m2[1][8]*m1[2][3]*m0[0][5]+m2[1][8]*m1[0][5]*m0[2][3]+m2[1][8]*m1[0][3]*m0[2][5]-m2[1][6]*m1[2][5]*m0[0][5]+m2[1][6]*m1[0][5]*m0[2][5]-m2[1][5]*m1[2][8]*m0[0][3]-m2[1][5]*m1[2][6]*m0[0][5]-m2[1][5]*m1[2][5]*m0[0][6]-m2[1][5]*m1[2][3]*m0[0][8]+m2[1][5]*m1[0][8]*m0[2][3]+m2[1][5]*m1[0][6]*m0[2][5]+m2[1][5]*m1[0][5]*m0[2][6]+m2[1][5]*m1[0][3]*m0[2][8]-m2[1][3]*m1[2][8]*m0[0][5]-m2[1][3]*m1[2][5]*m0[0][8]+m2[1][3]*m1[0][8]*m0[2][5]+m2[1][3]*m1[0][5]*m0[2][8]+m2[0][8]*m1[2][5]*m0[1][3]+m2[0][8]*m1[2][3]*m0[1][5]-m2[0][8]*m1[1][5]*m0[2][3]-m2[0][8]*m1[1][3]*m0[2][5]+m2[0][6]*m1[2][5]*m0[1][5]-m2[0][6]*m1[1][5]*m0[2][5]+m2[0][5]*m1[2][8]*m0[1][3]+m2[0][5]*m1[2][6]*m0[1][5]+m2[0][5]*m1[2][5]*m0[1][6]+m2[0][5]*m1[2][3]*m0[1][8]-m2[0][5]*m1[1][8]*m0[2][3]-m2[0][5]*m1[1][6]*m0[2][5]-m2[0][5]*m1[1][5]*m0[2][6]-m2[0][5]*m1[1][3]*m0[2][8]+m2[0][3]*m1[2][8]*m0[1][5]+m2[0][3]*m1[2][5]*m0[1][8]-m2[0][3]*m1[1][8]*m0[2][5]-m2[0][3]*m1[1][5]*m0[2][8]; M1(row,47) = m2[2][8]*m1[1][5]*m0[0][4]+m2[2][8]*m1[1][4]*m0[0][5]-m2[2][8]*m1[0][5]*m0[1][4]-m2[2][8]*m1[0][4]*m0[1][5]+m2[2][7]*m1[1][5]*m0[0][5]-m2[2][7]*m1[0][5]*m0[1][5]+m2[2][5]*m1[1][8]*m0[0][4]+m2[2][5]*m1[1][7]*m0[0][5]+m2[2][5]*m1[1][5]*m0[0][7]+m2[2][5]*m1[1][4]*m0[0][8]-m2[2][5]*m1[0][8]*m0[1][4]-m2[2][5]*m1[0][7]*m0[1][5]-m2[2][5]*m1[0][5]*m0[1][7]-m2[2][5]*m1[0][4]*m0[1][8]+m2[2][4]*m1[1][8]*m0[0][5]+m2[2][4]*m1[1][5]*m0[0][8]-m2[2][4]*m1[0][8]*m0[1][5]-m2[2][4]*m1[0][5]*m0[1][8]-m2[1][8]*m1[2][5]*m0[0][4]-m2[1][8]*m1[2][4]*m0[0][5]+m2[1][8]*m1[0][5]*m0[2][4]+m2[1][8]*m1[0][4]*m0[2][5]-m2[1][7]*m1[2][5]*m0[0][5]+m2[1][7]*m1[0][5]*m0[2][5]-m2[1][5]*m1[2][8]*m0[0][4]-m2[1][5]*m1[2][7]*m0[0][5]-m2[1][5]*m1[2][5]*m0[0][7]-m2[1][5]*m1[2][4]*m0[0][8]+m2[1][5]*m1[0][8]*m0[2][4]+m2[1][5]*m1[0][7]*m0[2][5]+m2[1][5]*m1[0][5]*m0[2][7]+m2[1][5]*m1[0][4]*m0[2][8]-m2[1][4]*m1[2][8]*m0[0][5]-m2[1][4]*m1[2][5]*m0[0][8]+m2[1][4]*m1[0][8]*m0[2][5]+m2[1][4]*m1[0][5]*m0[2][8]+m2[0][8]*m1[2][5]*m0[1][4]+m2[0][8]*m1[2][4]*m0[1][5]-m2[0][8]*m1[1][5]*m0[2][4]-m2[0][8]*m1[1][4]*m0[2][5]+m2[0][7]*m1[2][5]*m0[1][5]-m2[0][7]*m1[1][5]*m0[2][5]+m2[0][5]*m1[2][8]*m0[1][4]+m2[0][5]*m1[2][7]*m0[1][5]+m2[0][5]*m1[2][5]*m0[1][7]+m2[0][5]*m1[2][4]*m0[1][8]-m2[0][5]*m1[1][8]*m0[2][4]-m2[0][5]*m1[1][7]*m0[2][5]-m2[0][5]*m1[1][5]*m0[2][7]-m2[0][5]*m1[1][4]*m0[2][8]+m2[0][4]*m1[2][8]*m0[1][5]+m2[0][4]*m1[2][5]*m0[1][8]-m2[0][4]*m1[1][8]*m0[2][5]-m2[0][4]*m1[1][5]*m0[2][8]; M1(row,48) = m2[2][8]*m1[1][5]*m0[0][5]-m2[2][8]*m1[0][5]*m0[1][5]+m2[2][5]*m1[1][8]*m0[0][5]+m2[2][5]*m1[1][5]*m0[0][8]-m2[2][5]*m1[0][8]*m0[1][5]-m2[2][5]*m1[0][5]*m0[1][8]-m2[1][8]*m1[2][5]*m0[0][5]+m2[1][8]*m1[0][5]*m0[2][5]-m2[1][5]*m1[2][8]*m0[0][5]-m2[1][5]*m1[2][5]*m0[0][8]+m2[1][5]*m1[0][8]*m0[2][5]+m2[1][5]*m1[0][5]*m0[2][8]+m2[0][8]*m1[2][5]*m0[1][5]-m2[0][8]*m1[1][5]*m0[2][5]+m2[0][5]*m1[2][8]*m0[1][5]+m2[0][5]*m1[2][5]*m0[1][8]-m2[0][5]*m1[1][8]*m0[2][5]-m2[0][5]*m1[1][5]*m0[2][8]; M1(row,49) = m2[2][9]*m1[1][0]*m0[0][0]-m2[2][9]*m1[0][0]*m0[1][0]+m2[2][6]*m1[1][6]*m0[0][0]+m2[2][6]*m1[1][0]*m0[0][6]-m2[2][6]*m1[0][6]*m0[1][0]-m2[2][6]*m1[0][0]*m0[1][6]+m2[2][0]*m1[1][9]*m0[0][0]+m2[2][0]*m1[1][6]*m0[0][6]+m2[2][0]*m1[1][0]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][0]-m2[2][0]*m1[0][6]*m0[1][6]-m2[2][0]*m1[0][0]*m0[1][9]-m2[1][9]*m1[2][0]*m0[0][0]+m2[1][9]*m1[0][0]*m0[2][0]-m2[1][6]*m1[2][6]*m0[0][0]-m2[1][6]*m1[2][0]*m0[0][6]+m2[1][6]*m1[0][6]*m0[2][0]+m2[1][6]*m1[0][0]*m0[2][6]-m2[1][0]*m1[2][9]*m0[0][0]-m2[1][0]*m1[2][6]*m0[0][6]-m2[1][0]*m1[2][0]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][0]+m2[1][0]*m1[0][6]*m0[2][6]+m2[1][0]*m1[0][0]*m0[2][9]+m2[0][9]*m1[2][0]*m0[1][0]-m2[0][9]*m1[1][0]*m0[2][0]+m2[0][6]*m1[2][6]*m0[1][0]+m2[0][6]*m1[2][0]*m0[1][6]-m2[0][6]*m1[1][6]*m0[2][0]-m2[0][6]*m1[1][0]*m0[2][6]+m2[0][0]*m1[2][9]*m0[1][0]+m2[0][0]*m1[2][6]*m0[1][6]+m2[0][0]*m1[2][0]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][0]-m2[0][0]*m1[1][6]*m0[2][6]-m2[0][0]*m1[1][0]*m0[2][9]; M1(row,50) = m2[2][9]*m1[1][1]*m0[0][0]+m2[2][9]*m1[1][0]*m0[0][1]-m2[2][9]*m1[0][1]*m0[1][0]-m2[2][9]*m1[0][0]*m0[1][1]+m2[2][7]*m1[1][6]*m0[0][0]+m2[2][7]*m1[1][0]*m0[0][6]-m2[2][7]*m1[0][6]*m0[1][0]-m2[2][7]*m1[0][0]*m0[1][6]+m2[2][6]*m1[1][7]*m0[0][0]+m2[2][6]*m1[1][6]*m0[0][1]+m2[2][6]*m1[1][1]*m0[0][6]+m2[2][6]*m1[1][0]*m0[0][7]-m2[2][6]*m1[0][7]*m0[1][0]-m2[2][6]*m1[0][6]*m0[1][1]-m2[2][6]*m1[0][1]*m0[1][6]-m2[2][6]*m1[0][0]*m0[1][7]+m2[2][1]*m1[1][9]*m0[0][0]+m2[2][1]*m1[1][6]*m0[0][6]+m2[2][1]*m1[1][0]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][0]-m2[2][1]*m1[0][6]*m0[1][6]-m2[2][1]*m1[0][0]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][1]+m2[2][0]*m1[1][7]*m0[0][6]+m2[2][0]*m1[1][6]*m0[0][7]+m2[2][0]*m1[1][1]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][1]-m2[2][0]*m1[0][7]*m0[1][6]-m2[2][0]*m1[0][6]*m0[1][7]-m2[2][0]*m1[0][1]*m0[1][9]-m2[1][9]*m1[2][1]*m0[0][0]-m2[1][9]*m1[2][0]*m0[0][1]+m2[1][9]*m1[0][1]*m0[2][0]+m2[1][9]*m1[0][0]*m0[2][1]-m2[1][7]*m1[2][6]*m0[0][0]-m2[1][7]*m1[2][0]*m0[0][6]+m2[1][7]*m1[0][6]*m0[2][0]+m2[1][7]*m1[0][0]*m0[2][6]-m2[1][6]*m1[2][7]*m0[0][0]-m2[1][6]*m1[2][6]*m0[0][1]-m2[1][6]*m1[2][1]*m0[0][6]-m2[1][6]*m1[2][0]*m0[0][7]+m2[1][6]*m1[0][7]*m0[2][0]+m2[1][6]*m1[0][6]*m0[2][1]+m2[1][6]*m1[0][1]*m0[2][6]+m2[1][6]*m1[0][0]*m0[2][7]-m2[1][1]*m1[2][9]*m0[0][0]-m2[1][1]*m1[2][6]*m0[0][6]-m2[1][1]*m1[2][0]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][0]+m2[1][1]*m1[0][6]*m0[2][6]+m2[1][1]*m1[0][0]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][1]-m2[1][0]*m1[2][7]*m0[0][6]-m2[1][0]*m1[2][6]*m0[0][7]-m2[1][0]*m1[2][1]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][1]+m2[1][0]*m1[0][7]*m0[2][6]+m2[1][0]*m1[0][6]*m0[2][7]+m2[1][0]*m1[0][1]*m0[2][9]+m2[0][9]*m1[2][1]*m0[1][0]+m2[0][9]*m1[2][0]*m0[1][1]-m2[0][9]*m1[1][1]*m0[2][0]-m2[0][9]*m1[1][0]*m0[2][1]+m2[0][7]*m1[2][6]*m0[1][0]+m2[0][7]*m1[2][0]*m0[1][6]-m2[0][7]*m1[1][6]*m0[2][0]-m2[0][7]*m1[1][0]*m0[2][6]+m2[0][6]*m1[2][7]*m0[1][0]+m2[0][6]*m1[2][6]*m0[1][1]+m2[0][6]*m1[2][1]*m0[1][6]+m2[0][6]*m1[2][0]*m0[1][7]-m2[0][6]*m1[1][7]*m0[2][0]-m2[0][6]*m1[1][6]*m0[2][1]-m2[0][6]*m1[1][1]*m0[2][6]-m2[0][6]*m1[1][0]*m0[2][7]+m2[0][1]*m1[2][9]*m0[1][0]+m2[0][1]*m1[2][6]*m0[1][6]+m2[0][1]*m1[2][0]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][0]-m2[0][1]*m1[1][6]*m0[2][6]-m2[0][1]*m1[1][0]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][1]+m2[0][0]*m1[2][7]*m0[1][6]+m2[0][0]*m1[2][6]*m0[1][7]+m2[0][0]*m1[2][1]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][1]-m2[0][0]*m1[1][7]*m0[2][6]-m2[0][0]*m1[1][6]*m0[2][7]-m2[0][0]*m1[1][1]*m0[2][9]; M1(row,51) = m2[2][9]*m1[1][2]*m0[0][0]+m2[2][9]*m1[1][1]*m0[0][1]+m2[2][9]*m1[1][0]*m0[0][2]-m2[2][9]*m1[0][2]*m0[1][0]-m2[2][9]*m1[0][1]*m0[1][1]-m2[2][9]*m1[0][0]*m0[1][2]+m2[2][7]*m1[1][7]*m0[0][0]+m2[2][7]*m1[1][6]*m0[0][1]+m2[2][7]*m1[1][1]*m0[0][6]+m2[2][7]*m1[1][0]*m0[0][7]-m2[2][7]*m1[0][7]*m0[1][0]-m2[2][7]*m1[0][6]*m0[1][1]-m2[2][7]*m1[0][1]*m0[1][6]-m2[2][7]*m1[0][0]*m0[1][7]+m2[2][6]*m1[1][7]*m0[0][1]+m2[2][6]*m1[1][6]*m0[0][2]+m2[2][6]*m1[1][2]*m0[0][6]+m2[2][6]*m1[1][1]*m0[0][7]-m2[2][6]*m1[0][7]*m0[1][1]-m2[2][6]*m1[0][6]*m0[1][2]-m2[2][6]*m1[0][2]*m0[1][6]-m2[2][6]*m1[0][1]*m0[1][7]+m2[2][2]*m1[1][9]*m0[0][0]+m2[2][2]*m1[1][6]*m0[0][6]+m2[2][2]*m1[1][0]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][0]-m2[2][2]*m1[0][6]*m0[1][6]-m2[2][2]*m1[0][0]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][1]+m2[2][1]*m1[1][7]*m0[0][6]+m2[2][1]*m1[1][6]*m0[0][7]+m2[2][1]*m1[1][1]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][1]-m2[2][1]*m1[0][7]*m0[1][6]-m2[2][1]*m1[0][6]*m0[1][7]-m2[2][1]*m1[0][1]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][2]+m2[2][0]*m1[1][7]*m0[0][7]+m2[2][0]*m1[1][2]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][2]-m2[2][0]*m1[0][7]*m0[1][7]-m2[2][0]*m1[0][2]*m0[1][9]-m2[1][9]*m1[2][2]*m0[0][0]-m2[1][9]*m1[2][1]*m0[0][1]-m2[1][9]*m1[2][0]*m0[0][2]+m2[1][9]*m1[0][2]*m0[2][0]+m2[1][9]*m1[0][1]*m0[2][1]+m2[1][9]*m1[0][0]*m0[2][2]-m2[1][7]*m1[2][7]*m0[0][0]-m2[1][7]*m1[2][6]*m0[0][1]-m2[1][7]*m1[2][1]*m0[0][6]-m2[1][7]*m1[2][0]*m0[0][7]+m2[1][7]*m1[0][7]*m0[2][0]+m2[1][7]*m1[0][6]*m0[2][1]+m2[1][7]*m1[0][1]*m0[2][6]+m2[1][7]*m1[0][0]*m0[2][7]-m2[1][6]*m1[2][7]*m0[0][1]-m2[1][6]*m1[2][6]*m0[0][2]-m2[1][6]*m1[2][2]*m0[0][6]-m2[1][6]*m1[2][1]*m0[0][7]+m2[1][6]*m1[0][7]*m0[2][1]+m2[1][6]*m1[0][6]*m0[2][2]+m2[1][6]*m1[0][2]*m0[2][6]+m2[1][6]*m1[0][1]*m0[2][7]-m2[1][2]*m1[2][9]*m0[0][0]-m2[1][2]*m1[2][6]*m0[0][6]-m2[1][2]*m1[2][0]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][0]+m2[1][2]*m1[0][6]*m0[2][6]+m2[1][2]*m1[0][0]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][1]-m2[1][1]*m1[2][7]*m0[0][6]-m2[1][1]*m1[2][6]*m0[0][7]-m2[1][1]*m1[2][1]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][1]+m2[1][1]*m1[0][7]*m0[2][6]+m2[1][1]*m1[0][6]*m0[2][7]+m2[1][1]*m1[0][1]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][2]-m2[1][0]*m1[2][7]*m0[0][7]-m2[1][0]*m1[2][2]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][2]+m2[1][0]*m1[0][7]*m0[2][7]+m2[1][0]*m1[0][2]*m0[2][9]+m2[0][9]*m1[2][2]*m0[1][0]+m2[0][9]*m1[2][1]*m0[1][1]+m2[0][9]*m1[2][0]*m0[1][2]-m2[0][9]*m1[1][2]*m0[2][0]-m2[0][9]*m1[1][1]*m0[2][1]-m2[0][9]*m1[1][0]*m0[2][2]+m2[0][7]*m1[2][7]*m0[1][0]+m2[0][7]*m1[2][6]*m0[1][1]+m2[0][7]*m1[2][1]*m0[1][6]+m2[0][7]*m1[2][0]*m0[1][7]-m2[0][7]*m1[1][7]*m0[2][0]-m2[0][7]*m1[1][6]*m0[2][1]-m2[0][7]*m1[1][1]*m0[2][6]-m2[0][7]*m1[1][0]*m0[2][7]+m2[0][6]*m1[2][7]*m0[1][1]+m2[0][6]*m1[2][6]*m0[1][2]+m2[0][6]*m1[2][2]*m0[1][6]+m2[0][6]*m1[2][1]*m0[1][7]-m2[0][6]*m1[1][7]*m0[2][1]-m2[0][6]*m1[1][6]*m0[2][2]-m2[0][6]*m1[1][2]*m0[2][6]-m2[0][6]*m1[1][1]*m0[2][7]+m2[0][2]*m1[2][9]*m0[1][0]+m2[0][2]*m1[2][6]*m0[1][6]+m2[0][2]*m1[2][0]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][0]-m2[0][2]*m1[1][6]*m0[2][6]-m2[0][2]*m1[1][0]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][1]+m2[0][1]*m1[2][7]*m0[1][6]+m2[0][1]*m1[2][6]*m0[1][7]+m2[0][1]*m1[2][1]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][1]-m2[0][1]*m1[1][7]*m0[2][6]-m2[0][1]*m1[1][6]*m0[2][7]-m2[0][1]*m1[1][1]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][2]+m2[0][0]*m1[2][7]*m0[1][7]+m2[0][0]*m1[2][2]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][2]-m2[0][0]*m1[1][7]*m0[2][7]-m2[0][0]*m1[1][2]*m0[2][9]; M1(row,52) = m2[2][9]*m1[1][2]*m0[0][1]+m2[2][9]*m1[1][1]*m0[0][2]-m2[2][9]*m1[0][2]*m0[1][1]-m2[2][9]*m1[0][1]*m0[1][2]+m2[2][7]*m1[1][7]*m0[0][1]+m2[2][7]*m1[1][6]*m0[0][2]+m2[2][7]*m1[1][2]*m0[0][6]+m2[2][7]*m1[1][1]*m0[0][7]-m2[2][7]*m1[0][7]*m0[1][1]-m2[2][7]*m1[0][6]*m0[1][2]-m2[2][7]*m1[0][2]*m0[1][6]-m2[2][7]*m1[0][1]*m0[1][7]+m2[2][6]*m1[1][7]*m0[0][2]+m2[2][6]*m1[1][2]*m0[0][7]-m2[2][6]*m1[0][7]*m0[1][2]-m2[2][6]*m1[0][2]*m0[1][7]+m2[2][2]*m1[1][9]*m0[0][1]+m2[2][2]*m1[1][7]*m0[0][6]+m2[2][2]*m1[1][6]*m0[0][7]+m2[2][2]*m1[1][1]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][1]-m2[2][2]*m1[0][7]*m0[1][6]-m2[2][2]*m1[0][6]*m0[1][7]-m2[2][2]*m1[0][1]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][2]+m2[2][1]*m1[1][7]*m0[0][7]+m2[2][1]*m1[1][2]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][2]-m2[2][1]*m1[0][7]*m0[1][7]-m2[2][1]*m1[0][2]*m0[1][9]-m2[1][9]*m1[2][2]*m0[0][1]-m2[1][9]*m1[2][1]*m0[0][2]+m2[1][9]*m1[0][2]*m0[2][1]+m2[1][9]*m1[0][1]*m0[2][2]-m2[1][7]*m1[2][7]*m0[0][1]-m2[1][7]*m1[2][6]*m0[0][2]-m2[1][7]*m1[2][2]*m0[0][6]-m2[1][7]*m1[2][1]*m0[0][7]+m2[1][7]*m1[0][7]*m0[2][1]+m2[1][7]*m1[0][6]*m0[2][2]+m2[1][7]*m1[0][2]*m0[2][6]+m2[1][7]*m1[0][1]*m0[2][7]-m2[1][6]*m1[2][7]*m0[0][2]-m2[1][6]*m1[2][2]*m0[0][7]+m2[1][6]*m1[0][7]*m0[2][2]+m2[1][6]*m1[0][2]*m0[2][7]-m2[1][2]*m1[2][9]*m0[0][1]-m2[1][2]*m1[2][7]*m0[0][6]-m2[1][2]*m1[2][6]*m0[0][7]-m2[1][2]*m1[2][1]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][1]+m2[1][2]*m1[0][7]*m0[2][6]+m2[1][2]*m1[0][6]*m0[2][7]+m2[1][2]*m1[0][1]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][2]-m2[1][1]*m1[2][7]*m0[0][7]-m2[1][1]*m1[2][2]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][2]+m2[1][1]*m1[0][7]*m0[2][7]+m2[1][1]*m1[0][2]*m0[2][9]+m2[0][9]*m1[2][2]*m0[1][1]+m2[0][9]*m1[2][1]*m0[1][2]-m2[0][9]*m1[1][2]*m0[2][1]-m2[0][9]*m1[1][1]*m0[2][2]+m2[0][7]*m1[2][7]*m0[1][1]+m2[0][7]*m1[2][6]*m0[1][2]+m2[0][7]*m1[2][2]*m0[1][6]+m2[0][7]*m1[2][1]*m0[1][7]-m2[0][7]*m1[1][7]*m0[2][1]-m2[0][7]*m1[1][6]*m0[2][2]-m2[0][7]*m1[1][2]*m0[2][6]-m2[0][7]*m1[1][1]*m0[2][7]+m2[0][6]*m1[2][7]*m0[1][2]+m2[0][6]*m1[2][2]*m0[1][7]-m2[0][6]*m1[1][7]*m0[2][2]-m2[0][6]*m1[1][2]*m0[2][7]+m2[0][2]*m1[2][9]*m0[1][1]+m2[0][2]*m1[2][7]*m0[1][6]+m2[0][2]*m1[2][6]*m0[1][7]+m2[0][2]*m1[2][1]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][1]-m2[0][2]*m1[1][7]*m0[2][6]-m2[0][2]*m1[1][6]*m0[2][7]-m2[0][2]*m1[1][1]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][2]+m2[0][1]*m1[2][7]*m0[1][7]+m2[0][1]*m1[2][2]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][2]-m2[0][1]*m1[1][7]*m0[2][7]-m2[0][1]*m1[1][2]*m0[2][9]; M1(row,53) = m2[2][9]*m1[1][2]*m0[0][2]-m2[2][9]*m1[0][2]*m0[1][2]+m2[2][7]*m1[1][7]*m0[0][2]+m2[2][7]*m1[1][2]*m0[0][7]-m2[2][7]*m1[0][7]*m0[1][2]-m2[2][7]*m1[0][2]*m0[1][7]+m2[2][2]*m1[1][9]*m0[0][2]+m2[2][2]*m1[1][7]*m0[0][7]+m2[2][2]*m1[1][2]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][2]-m2[2][2]*m1[0][7]*m0[1][7]-m2[2][2]*m1[0][2]*m0[1][9]-m2[1][9]*m1[2][2]*m0[0][2]+m2[1][9]*m1[0][2]*m0[2][2]-m2[1][7]*m1[2][7]*m0[0][2]-m2[1][7]*m1[2][2]*m0[0][7]+m2[1][7]*m1[0][7]*m0[2][2]+m2[1][7]*m1[0][2]*m0[2][7]-m2[1][2]*m1[2][9]*m0[0][2]-m2[1][2]*m1[2][7]*m0[0][7]-m2[1][2]*m1[2][2]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][2]+m2[1][2]*m1[0][7]*m0[2][7]+m2[1][2]*m1[0][2]*m0[2][9]+m2[0][9]*m1[2][2]*m0[1][2]-m2[0][9]*m1[1][2]*m0[2][2]+m2[0][7]*m1[2][7]*m0[1][2]+m2[0][7]*m1[2][2]*m0[1][7]-m2[0][7]*m1[1][7]*m0[2][2]-m2[0][7]*m1[1][2]*m0[2][7]+m2[0][2]*m1[2][9]*m0[1][2]+m2[0][2]*m1[2][7]*m0[1][7]+m2[0][2]*m1[2][2]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][2]-m2[0][2]*m1[1][7]*m0[2][7]-m2[0][2]*m1[1][2]*m0[2][9]; M1(row,54) = m2[2][9]*m1[1][3]*m0[0][0]+m2[2][9]*m1[1][0]*m0[0][3]-m2[2][9]*m1[0][3]*m0[1][0]-m2[2][9]*m1[0][0]*m0[1][3]+m2[2][8]*m1[1][6]*m0[0][0]+m2[2][8]*m1[1][0]*m0[0][6]-m2[2][8]*m1[0][6]*m0[1][0]-m2[2][8]*m1[0][0]*m0[1][6]+m2[2][6]*m1[1][8]*m0[0][0]+m2[2][6]*m1[1][6]*m0[0][3]+m2[2][6]*m1[1][3]*m0[0][6]+m2[2][6]*m1[1][0]*m0[0][8]-m2[2][6]*m1[0][8]*m0[1][0]-m2[2][6]*m1[0][6]*m0[1][3]-m2[2][6]*m1[0][3]*m0[1][6]-m2[2][6]*m1[0][0]*m0[1][8]+m2[2][3]*m1[1][9]*m0[0][0]+m2[2][3]*m1[1][6]*m0[0][6]+m2[2][3]*m1[1][0]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][0]-m2[2][3]*m1[0][6]*m0[1][6]-m2[2][3]*m1[0][0]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][3]+m2[2][0]*m1[1][8]*m0[0][6]+m2[2][0]*m1[1][6]*m0[0][8]+m2[2][0]*m1[1][3]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][3]-m2[2][0]*m1[0][8]*m0[1][6]-m2[2][0]*m1[0][6]*m0[1][8]-m2[2][0]*m1[0][3]*m0[1][9]-m2[1][9]*m1[2][3]*m0[0][0]-m2[1][9]*m1[2][0]*m0[0][3]+m2[1][9]*m1[0][3]*m0[2][0]+m2[1][9]*m1[0][0]*m0[2][3]-m2[1][8]*m1[2][6]*m0[0][0]-m2[1][8]*m1[2][0]*m0[0][6]+m2[1][8]*m1[0][6]*m0[2][0]+m2[1][8]*m1[0][0]*m0[2][6]-m2[1][6]*m1[2][8]*m0[0][0]-m2[1][6]*m1[2][6]*m0[0][3]-m2[1][6]*m1[2][3]*m0[0][6]-m2[1][6]*m1[2][0]*m0[0][8]+m2[1][6]*m1[0][8]*m0[2][0]+m2[1][6]*m1[0][6]*m0[2][3]+m2[1][6]*m1[0][3]*m0[2][6]+m2[1][6]*m1[0][0]*m0[2][8]-m2[1][3]*m1[2][9]*m0[0][0]-m2[1][3]*m1[2][6]*m0[0][6]-m2[1][3]*m1[2][0]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][0]+m2[1][3]*m1[0][6]*m0[2][6]+m2[1][3]*m1[0][0]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][3]-m2[1][0]*m1[2][8]*m0[0][6]-m2[1][0]*m1[2][6]*m0[0][8]-m2[1][0]*m1[2][3]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][3]+m2[1][0]*m1[0][8]*m0[2][6]+m2[1][0]*m1[0][6]*m0[2][8]+m2[1][0]*m1[0][3]*m0[2][9]+m2[0][9]*m1[2][3]*m0[1][0]+m2[0][9]*m1[2][0]*m0[1][3]-m2[0][9]*m1[1][3]*m0[2][0]-m2[0][9]*m1[1][0]*m0[2][3]+m2[0][8]*m1[2][6]*m0[1][0]+m2[0][8]*m1[2][0]*m0[1][6]-m2[0][8]*m1[1][6]*m0[2][0]-m2[0][8]*m1[1][0]*m0[2][6]+m2[0][6]*m1[2][8]*m0[1][0]+m2[0][6]*m1[2][6]*m0[1][3]+m2[0][6]*m1[2][3]*m0[1][6]+m2[0][6]*m1[2][0]*m0[1][8]-m2[0][6]*m1[1][8]*m0[2][0]-m2[0][6]*m1[1][6]*m0[2][3]-m2[0][6]*m1[1][3]*m0[2][6]-m2[0][6]*m1[1][0]*m0[2][8]+m2[0][3]*m1[2][9]*m0[1][0]+m2[0][3]*m1[2][6]*m0[1][6]+m2[0][3]*m1[2][0]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][0]-m2[0][3]*m1[1][6]*m0[2][6]-m2[0][3]*m1[1][0]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][3]+m2[0][0]*m1[2][8]*m0[1][6]+m2[0][0]*m1[2][6]*m0[1][8]+m2[0][0]*m1[2][3]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][3]-m2[0][0]*m1[1][8]*m0[2][6]-m2[0][0]*m1[1][6]*m0[2][8]-m2[0][0]*m1[1][3]*m0[2][9]; M1(row,55) = m2[2][9]*m1[1][4]*m0[0][0]+m2[2][9]*m1[1][3]*m0[0][1]+m2[2][9]*m1[1][1]*m0[0][3]+m2[2][9]*m1[1][0]*m0[0][4]-m2[2][9]*m1[0][4]*m0[1][0]-m2[2][9]*m1[0][3]*m0[1][1]-m2[2][9]*m1[0][1]*m0[1][3]-m2[2][9]*m1[0][0]*m0[1][4]+m2[2][8]*m1[1][7]*m0[0][0]+m2[2][8]*m1[1][6]*m0[0][1]+m2[2][8]*m1[1][1]*m0[0][6]+m2[2][8]*m1[1][0]*m0[0][7]-m2[2][8]*m1[0][7]*m0[1][0]-m2[2][8]*m1[0][6]*m0[1][1]-m2[2][8]*m1[0][1]*m0[1][6]-m2[2][8]*m1[0][0]*m0[1][7]+m2[2][7]*m1[1][8]*m0[0][0]+m2[2][7]*m1[1][6]*m0[0][3]+m2[2][7]*m1[1][3]*m0[0][6]+m2[2][7]*m1[1][0]*m0[0][8]-m2[2][7]*m1[0][8]*m0[1][0]-m2[2][7]*m1[0][6]*m0[1][3]-m2[2][7]*m1[0][3]*m0[1][6]-m2[2][7]*m1[0][0]*m0[1][8]+m2[2][6]*m1[1][8]*m0[0][1]+m2[2][6]*m1[1][7]*m0[0][3]+m2[2][6]*m1[1][6]*m0[0][4]+m2[2][6]*m1[1][4]*m0[0][6]+m2[2][6]*m1[1][3]*m0[0][7]+m2[2][6]*m1[1][1]*m0[0][8]-m2[2][6]*m1[0][8]*m0[1][1]-m2[2][6]*m1[0][7]*m0[1][3]-m2[2][6]*m1[0][6]*m0[1][4]-m2[2][6]*m1[0][4]*m0[1][6]-m2[2][6]*m1[0][3]*m0[1][7]-m2[2][6]*m1[0][1]*m0[1][8]+m2[2][4]*m1[1][9]*m0[0][0]+m2[2][4]*m1[1][6]*m0[0][6]+m2[2][4]*m1[1][0]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][0]-m2[2][4]*m1[0][6]*m0[1][6]-m2[2][4]*m1[0][0]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][1]+m2[2][3]*m1[1][7]*m0[0][6]+m2[2][3]*m1[1][6]*m0[0][7]+m2[2][3]*m1[1][1]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][1]-m2[2][3]*m1[0][7]*m0[1][6]-m2[2][3]*m1[0][6]*m0[1][7]-m2[2][3]*m1[0][1]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][3]+m2[2][1]*m1[1][8]*m0[0][6]+m2[2][1]*m1[1][6]*m0[0][8]+m2[2][1]*m1[1][3]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][3]-m2[2][1]*m1[0][8]*m0[1][6]-m2[2][1]*m1[0][6]*m0[1][8]-m2[2][1]*m1[0][3]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][4]+m2[2][0]*m1[1][8]*m0[0][7]+m2[2][0]*m1[1][7]*m0[0][8]+m2[2][0]*m1[1][4]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][4]-m2[2][0]*m1[0][8]*m0[1][7]-m2[2][0]*m1[0][7]*m0[1][8]-m2[2][0]*m1[0][4]*m0[1][9]-m2[1][9]*m1[2][4]*m0[0][0]-m2[1][9]*m1[2][3]*m0[0][1]-m2[1][9]*m1[2][1]*m0[0][3]-m2[1][9]*m1[2][0]*m0[0][4]+m2[1][9]*m1[0][4]*m0[2][0]+m2[1][9]*m1[0][3]*m0[2][1]+m2[1][9]*m1[0][1]*m0[2][3]+m2[1][9]*m1[0][0]*m0[2][4]-m2[1][8]*m1[2][7]*m0[0][0]-m2[1][8]*m1[2][6]*m0[0][1]-m2[1][8]*m1[2][1]*m0[0][6]-m2[1][8]*m1[2][0]*m0[0][7]+m2[1][8]*m1[0][7]*m0[2][0]+m2[1][8]*m1[0][6]*m0[2][1]+m2[1][8]*m1[0][1]*m0[2][6]+m2[1][8]*m1[0][0]*m0[2][7]-m2[1][7]*m1[2][8]*m0[0][0]-m2[1][7]*m1[2][6]*m0[0][3]-m2[1][7]*m1[2][3]*m0[0][6]-m2[1][7]*m1[2][0]*m0[0][8]+m2[1][7]*m1[0][8]*m0[2][0]+m2[1][7]*m1[0][6]*m0[2][3]+m2[1][7]*m1[0][3]*m0[2][6]+m2[1][7]*m1[0][0]*m0[2][8]-m2[1][6]*m1[2][8]*m0[0][1]-m2[1][6]*m1[2][7]*m0[0][3]-m2[1][6]*m1[2][6]*m0[0][4]-m2[1][6]*m1[2][4]*m0[0][6]-m2[1][6]*m1[2][3]*m0[0][7]-m2[1][6]*m1[2][1]*m0[0][8]+m2[1][6]*m1[0][8]*m0[2][1]+m2[1][6]*m1[0][7]*m0[2][3]+m2[1][6]*m1[0][6]*m0[2][4]+m2[1][6]*m1[0][4]*m0[2][6]+m2[1][6]*m1[0][3]*m0[2][7]+m2[1][6]*m1[0][1]*m0[2][8]-m2[1][4]*m1[2][9]*m0[0][0]-m2[1][4]*m1[2][6]*m0[0][6]-m2[1][4]*m1[2][0]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][0]+m2[1][4]*m1[0][6]*m0[2][6]+m2[1][4]*m1[0][0]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][1]-m2[1][3]*m1[2][7]*m0[0][6]-m2[1][3]*m1[2][6]*m0[0][7]-m2[1][3]*m1[2][1]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][1]+m2[1][3]*m1[0][7]*m0[2][6]+m2[1][3]*m1[0][6]*m0[2][7]+m2[1][3]*m1[0][1]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][3]-m2[1][1]*m1[2][8]*m0[0][6]-m2[1][1]*m1[2][6]*m0[0][8]-m2[1][1]*m1[2][3]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][3]+m2[1][1]*m1[0][8]*m0[2][6]+m2[1][1]*m1[0][6]*m0[2][8]+m2[1][1]*m1[0][3]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][4]-m2[1][0]*m1[2][8]*m0[0][7]-m2[1][0]*m1[2][7]*m0[0][8]-m2[1][0]*m1[2][4]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][4]+m2[1][0]*m1[0][8]*m0[2][7]+m2[1][0]*m1[0][7]*m0[2][8]+m2[1][0]*m1[0][4]*m0[2][9]+m2[0][9]*m1[2][4]*m0[1][0]+m2[0][9]*m1[2][3]*m0[1][1]+m2[0][9]*m1[2][1]*m0[1][3]+m2[0][9]*m1[2][0]*m0[1][4]-m2[0][9]*m1[1][4]*m0[2][0]-m2[0][9]*m1[1][3]*m0[2][1]-m2[0][9]*m1[1][1]*m0[2][3]-m2[0][9]*m1[1][0]*m0[2][4]+m2[0][8]*m1[2][7]*m0[1][0]+m2[0][8]*m1[2][6]*m0[1][1]+m2[0][8]*m1[2][1]*m0[1][6]+m2[0][8]*m1[2][0]*m0[1][7]-m2[0][8]*m1[1][7]*m0[2][0]-m2[0][8]*m1[1][6]*m0[2][1]-m2[0][8]*m1[1][1]*m0[2][6]-m2[0][8]*m1[1][0]*m0[2][7]+m2[0][7]*m1[2][8]*m0[1][0]+m2[0][7]*m1[2][6]*m0[1][3]+m2[0][7]*m1[2][3]*m0[1][6]+m2[0][7]*m1[2][0]*m0[1][8]-m2[0][7]*m1[1][8]*m0[2][0]-m2[0][7]*m1[1][6]*m0[2][3]-m2[0][7]*m1[1][3]*m0[2][6]-m2[0][7]*m1[1][0]*m0[2][8]+m2[0][6]*m1[2][8]*m0[1][1]+m2[0][6]*m1[2][7]*m0[1][3]+m2[0][6]*m1[2][6]*m0[1][4]+m2[0][6]*m1[2][4]*m0[1][6]+m2[0][6]*m1[2][3]*m0[1][7]+m2[0][6]*m1[2][1]*m0[1][8]-m2[0][6]*m1[1][8]*m0[2][1]-m2[0][6]*m1[1][7]*m0[2][3]-m2[0][6]*m1[1][6]*m0[2][4]-m2[0][6]*m1[1][4]*m0[2][6]-m2[0][6]*m1[1][3]*m0[2][7]-m2[0][6]*m1[1][1]*m0[2][8]+m2[0][4]*m1[2][9]*m0[1][0]+m2[0][4]*m1[2][6]*m0[1][6]+m2[0][4]*m1[2][0]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][0]-m2[0][4]*m1[1][6]*m0[2][6]-m2[0][4]*m1[1][0]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][1]+m2[0][3]*m1[2][7]*m0[1][6]+m2[0][3]*m1[2][6]*m0[1][7]+m2[0][3]*m1[2][1]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][1]-m2[0][3]*m1[1][7]*m0[2][6]-m2[0][3]*m1[1][6]*m0[2][7]-m2[0][3]*m1[1][1]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][3]+m2[0][1]*m1[2][8]*m0[1][6]+m2[0][1]*m1[2][6]*m0[1][8]+m2[0][1]*m1[2][3]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][3]-m2[0][1]*m1[1][8]*m0[2][6]-m2[0][1]*m1[1][6]*m0[2][8]-m2[0][1]*m1[1][3]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][4]+m2[0][0]*m1[2][8]*m0[1][7]+m2[0][0]*m1[2][7]*m0[1][8]+m2[0][0]*m1[2][4]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][4]-m2[0][0]*m1[1][8]*m0[2][7]-m2[0][0]*m1[1][7]*m0[2][8]-m2[0][0]*m1[1][4]*m0[2][9]; M1(row,56) = m2[2][9]*m1[1][4]*m0[0][1]+m2[2][9]*m1[1][3]*m0[0][2]+m2[2][9]*m1[1][2]*m0[0][3]+m2[2][9]*m1[1][1]*m0[0][4]-m2[2][9]*m1[0][4]*m0[1][1]-m2[2][9]*m1[0][3]*m0[1][2]-m2[2][9]*m1[0][2]*m0[1][3]-m2[2][9]*m1[0][1]*m0[1][4]+m2[2][8]*m1[1][7]*m0[0][1]+m2[2][8]*m1[1][6]*m0[0][2]+m2[2][8]*m1[1][2]*m0[0][6]+m2[2][8]*m1[1][1]*m0[0][7]-m2[2][8]*m1[0][7]*m0[1][1]-m2[2][8]*m1[0][6]*m0[1][2]-m2[2][8]*m1[0][2]*m0[1][6]-m2[2][8]*m1[0][1]*m0[1][7]+m2[2][7]*m1[1][8]*m0[0][1]+m2[2][7]*m1[1][7]*m0[0][3]+m2[2][7]*m1[1][6]*m0[0][4]+m2[2][7]*m1[1][4]*m0[0][6]+m2[2][7]*m1[1][3]*m0[0][7]+m2[2][7]*m1[1][1]*m0[0][8]-m2[2][7]*m1[0][8]*m0[1][1]-m2[2][7]*m1[0][7]*m0[1][3]-m2[2][7]*m1[0][6]*m0[1][4]-m2[2][7]*m1[0][4]*m0[1][6]-m2[2][7]*m1[0][3]*m0[1][7]-m2[2][7]*m1[0][1]*m0[1][8]+m2[2][6]*m1[1][8]*m0[0][2]+m2[2][6]*m1[1][7]*m0[0][4]+m2[2][6]*m1[1][4]*m0[0][7]+m2[2][6]*m1[1][2]*m0[0][8]-m2[2][6]*m1[0][8]*m0[1][2]-m2[2][6]*m1[0][7]*m0[1][4]-m2[2][6]*m1[0][4]*m0[1][7]-m2[2][6]*m1[0][2]*m0[1][8]+m2[2][4]*m1[1][9]*m0[0][1]+m2[2][4]*m1[1][7]*m0[0][6]+m2[2][4]*m1[1][6]*m0[0][7]+m2[2][4]*m1[1][1]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][1]-m2[2][4]*m1[0][7]*m0[1][6]-m2[2][4]*m1[0][6]*m0[1][7]-m2[2][4]*m1[0][1]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][2]+m2[2][3]*m1[1][7]*m0[0][7]+m2[2][3]*m1[1][2]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][2]-m2[2][3]*m1[0][7]*m0[1][7]-m2[2][3]*m1[0][2]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][3]+m2[2][2]*m1[1][8]*m0[0][6]+m2[2][2]*m1[1][6]*m0[0][8]+m2[2][2]*m1[1][3]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][3]-m2[2][2]*m1[0][8]*m0[1][6]-m2[2][2]*m1[0][6]*m0[1][8]-m2[2][2]*m1[0][3]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][4]+m2[2][1]*m1[1][8]*m0[0][7]+m2[2][1]*m1[1][7]*m0[0][8]+m2[2][1]*m1[1][4]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][4]-m2[2][1]*m1[0][8]*m0[1][7]-m2[2][1]*m1[0][7]*m0[1][8]-m2[2][1]*m1[0][4]*m0[1][9]-m2[1][9]*m1[2][4]*m0[0][1]-m2[1][9]*m1[2][3]*m0[0][2]-m2[1][9]*m1[2][2]*m0[0][3]-m2[1][9]*m1[2][1]*m0[0][4]+m2[1][9]*m1[0][4]*m0[2][1]+m2[1][9]*m1[0][3]*m0[2][2]+m2[1][9]*m1[0][2]*m0[2][3]+m2[1][9]*m1[0][1]*m0[2][4]-m2[1][8]*m1[2][7]*m0[0][1]-m2[1][8]*m1[2][6]*m0[0][2]-m2[1][8]*m1[2][2]*m0[0][6]-m2[1][8]*m1[2][1]*m0[0][7]+m2[1][8]*m1[0][7]*m0[2][1]+m2[1][8]*m1[0][6]*m0[2][2]+m2[1][8]*m1[0][2]*m0[2][6]+m2[1][8]*m1[0][1]*m0[2][7]-m2[1][7]*m1[2][8]*m0[0][1]-m2[1][7]*m1[2][7]*m0[0][3]-m2[1][7]*m1[2][6]*m0[0][4]-m2[1][7]*m1[2][4]*m0[0][6]-m2[1][7]*m1[2][3]*m0[0][7]-m2[1][7]*m1[2][1]*m0[0][8]+m2[1][7]*m1[0][8]*m0[2][1]+m2[1][7]*m1[0][7]*m0[2][3]+m2[1][7]*m1[0][6]*m0[2][4]+m2[1][7]*m1[0][4]*m0[2][6]+m2[1][7]*m1[0][3]*m0[2][7]+m2[1][7]*m1[0][1]*m0[2][8]-m2[1][6]*m1[2][8]*m0[0][2]-m2[1][6]*m1[2][7]*m0[0][4]-m2[1][6]*m1[2][4]*m0[0][7]-m2[1][6]*m1[2][2]*m0[0][8]+m2[1][6]*m1[0][8]*m0[2][2]+m2[1][6]*m1[0][7]*m0[2][4]+m2[1][6]*m1[0][4]*m0[2][7]+m2[1][6]*m1[0][2]*m0[2][8]-m2[1][4]*m1[2][9]*m0[0][1]-m2[1][4]*m1[2][7]*m0[0][6]-m2[1][4]*m1[2][6]*m0[0][7]-m2[1][4]*m1[2][1]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][1]+m2[1][4]*m1[0][7]*m0[2][6]+m2[1][4]*m1[0][6]*m0[2][7]+m2[1][4]*m1[0][1]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][2]-m2[1][3]*m1[2][7]*m0[0][7]-m2[1][3]*m1[2][2]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][2]+m2[1][3]*m1[0][7]*m0[2][7]+m2[1][3]*m1[0][2]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][3]-m2[1][2]*m1[2][8]*m0[0][6]-m2[1][2]*m1[2][6]*m0[0][8]-m2[1][2]*m1[2][3]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][3]+m2[1][2]*m1[0][8]*m0[2][6]+m2[1][2]*m1[0][6]*m0[2][8]+m2[1][2]*m1[0][3]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][4]-m2[1][1]*m1[2][8]*m0[0][7]-m2[1][1]*m1[2][7]*m0[0][8]-m2[1][1]*m1[2][4]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][4]+m2[1][1]*m1[0][8]*m0[2][7]+m2[1][1]*m1[0][7]*m0[2][8]+m2[1][1]*m1[0][4]*m0[2][9]+m2[0][9]*m1[2][4]*m0[1][1]+m2[0][9]*m1[2][3]*m0[1][2]+m2[0][9]*m1[2][2]*m0[1][3]+m2[0][9]*m1[2][1]*m0[1][4]-m2[0][9]*m1[1][4]*m0[2][1]-m2[0][9]*m1[1][3]*m0[2][2]-m2[0][9]*m1[1][2]*m0[2][3]-m2[0][9]*m1[1][1]*m0[2][4]+m2[0][8]*m1[2][7]*m0[1][1]+m2[0][8]*m1[2][6]*m0[1][2]+m2[0][8]*m1[2][2]*m0[1][6]+m2[0][8]*m1[2][1]*m0[1][7]-m2[0][8]*m1[1][7]*m0[2][1]-m2[0][8]*m1[1][6]*m0[2][2]-m2[0][8]*m1[1][2]*m0[2][6]-m2[0][8]*m1[1][1]*m0[2][7]+m2[0][7]*m1[2][8]*m0[1][1]+m2[0][7]*m1[2][7]*m0[1][3]+m2[0][7]*m1[2][6]*m0[1][4]+m2[0][7]*m1[2][4]*m0[1][6]+m2[0][7]*m1[2][3]*m0[1][7]+m2[0][7]*m1[2][1]*m0[1][8]-m2[0][7]*m1[1][8]*m0[2][1]-m2[0][7]*m1[1][7]*m0[2][3]-m2[0][7]*m1[1][6]*m0[2][4]-m2[0][7]*m1[1][4]*m0[2][6]-m2[0][7]*m1[1][3]*m0[2][7]-m2[0][7]*m1[1][1]*m0[2][8]+m2[0][6]*m1[2][8]*m0[1][2]+m2[0][6]*m1[2][7]*m0[1][4]+m2[0][6]*m1[2][4]*m0[1][7]+m2[0][6]*m1[2][2]*m0[1][8]-m2[0][6]*m1[1][8]*m0[2][2]-m2[0][6]*m1[1][7]*m0[2][4]-m2[0][6]*m1[1][4]*m0[2][7]-m2[0][6]*m1[1][2]*m0[2][8]+m2[0][4]*m1[2][9]*m0[1][1]+m2[0][4]*m1[2][7]*m0[1][6]+m2[0][4]*m1[2][6]*m0[1][7]+m2[0][4]*m1[2][1]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][1]-m2[0][4]*m1[1][7]*m0[2][6]-m2[0][4]*m1[1][6]*m0[2][7]-m2[0][4]*m1[1][1]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][2]+m2[0][3]*m1[2][7]*m0[1][7]+m2[0][3]*m1[2][2]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][2]-m2[0][3]*m1[1][7]*m0[2][7]-m2[0][3]*m1[1][2]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][3]+m2[0][2]*m1[2][8]*m0[1][6]+m2[0][2]*m1[2][6]*m0[1][8]+m2[0][2]*m1[2][3]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][3]-m2[0][2]*m1[1][8]*m0[2][6]-m2[0][2]*m1[1][6]*m0[2][8]-m2[0][2]*m1[1][3]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][4]+m2[0][1]*m1[2][8]*m0[1][7]+m2[0][1]*m1[2][7]*m0[1][8]+m2[0][1]*m1[2][4]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][4]-m2[0][1]*m1[1][8]*m0[2][7]-m2[0][1]*m1[1][7]*m0[2][8]-m2[0][1]*m1[1][4]*m0[2][9]; M1(row,57) = m2[2][9]*m1[1][4]*m0[0][2]+m2[2][9]*m1[1][2]*m0[0][4]-m2[2][9]*m1[0][4]*m0[1][2]-m2[2][9]*m1[0][2]*m0[1][4]+m2[2][8]*m1[1][7]*m0[0][2]+m2[2][8]*m1[1][2]*m0[0][7]-m2[2][8]*m1[0][7]*m0[1][2]-m2[2][8]*m1[0][2]*m0[1][7]+m2[2][7]*m1[1][8]*m0[0][2]+m2[2][7]*m1[1][7]*m0[0][4]+m2[2][7]*m1[1][4]*m0[0][7]+m2[2][7]*m1[1][2]*m0[0][8]-m2[2][7]*m1[0][8]*m0[1][2]-m2[2][7]*m1[0][7]*m0[1][4]-m2[2][7]*m1[0][4]*m0[1][7]-m2[2][7]*m1[0][2]*m0[1][8]+m2[2][4]*m1[1][9]*m0[0][2]+m2[2][4]*m1[1][7]*m0[0][7]+m2[2][4]*m1[1][2]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][2]-m2[2][4]*m1[0][7]*m0[1][7]-m2[2][4]*m1[0][2]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][4]+m2[2][2]*m1[1][8]*m0[0][7]+m2[2][2]*m1[1][7]*m0[0][8]+m2[2][2]*m1[1][4]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][4]-m2[2][2]*m1[0][8]*m0[1][7]-m2[2][2]*m1[0][7]*m0[1][8]-m2[2][2]*m1[0][4]*m0[1][9]-m2[1][9]*m1[2][4]*m0[0][2]-m2[1][9]*m1[2][2]*m0[0][4]+m2[1][9]*m1[0][4]*m0[2][2]+m2[1][9]*m1[0][2]*m0[2][4]-m2[1][8]*m1[2][7]*m0[0][2]-m2[1][8]*m1[2][2]*m0[0][7]+m2[1][8]*m1[0][7]*m0[2][2]+m2[1][8]*m1[0][2]*m0[2][7]-m2[1][7]*m1[2][8]*m0[0][2]-m2[1][7]*m1[2][7]*m0[0][4]-m2[1][7]*m1[2][4]*m0[0][7]-m2[1][7]*m1[2][2]*m0[0][8]+m2[1][7]*m1[0][8]*m0[2][2]+m2[1][7]*m1[0][7]*m0[2][4]+m2[1][7]*m1[0][4]*m0[2][7]+m2[1][7]*m1[0][2]*m0[2][8]-m2[1][4]*m1[2][9]*m0[0][2]-m2[1][4]*m1[2][7]*m0[0][7]-m2[1][4]*m1[2][2]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][2]+m2[1][4]*m1[0][7]*m0[2][7]+m2[1][4]*m1[0][2]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][4]-m2[1][2]*m1[2][8]*m0[0][7]-m2[1][2]*m1[2][7]*m0[0][8]-m2[1][2]*m1[2][4]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][4]+m2[1][2]*m1[0][8]*m0[2][7]+m2[1][2]*m1[0][7]*m0[2][8]+m2[1][2]*m1[0][4]*m0[2][9]+m2[0][9]*m1[2][4]*m0[1][2]+m2[0][9]*m1[2][2]*m0[1][4]-m2[0][9]*m1[1][4]*m0[2][2]-m2[0][9]*m1[1][2]*m0[2][4]+m2[0][8]*m1[2][7]*m0[1][2]+m2[0][8]*m1[2][2]*m0[1][7]-m2[0][8]*m1[1][7]*m0[2][2]-m2[0][8]*m1[1][2]*m0[2][7]+m2[0][7]*m1[2][8]*m0[1][2]+m2[0][7]*m1[2][7]*m0[1][4]+m2[0][7]*m1[2][4]*m0[1][7]+m2[0][7]*m1[2][2]*m0[1][8]-m2[0][7]*m1[1][8]*m0[2][2]-m2[0][7]*m1[1][7]*m0[2][4]-m2[0][7]*m1[1][4]*m0[2][7]-m2[0][7]*m1[1][2]*m0[2][8]+m2[0][4]*m1[2][9]*m0[1][2]+m2[0][4]*m1[2][7]*m0[1][7]+m2[0][4]*m1[2][2]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][2]-m2[0][4]*m1[1][7]*m0[2][7]-m2[0][4]*m1[1][2]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][4]+m2[0][2]*m1[2][8]*m0[1][7]+m2[0][2]*m1[2][7]*m0[1][8]+m2[0][2]*m1[2][4]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][4]-m2[0][2]*m1[1][8]*m0[2][7]-m2[0][2]*m1[1][7]*m0[2][8]-m2[0][2]*m1[1][4]*m0[2][9]; M1(row,58) = m2[2][9]*m1[1][5]*m0[0][0]+m2[2][9]*m1[1][3]*m0[0][3]+m2[2][9]*m1[1][0]*m0[0][5]-m2[2][9]*m1[0][5]*m0[1][0]-m2[2][9]*m1[0][3]*m0[1][3]-m2[2][9]*m1[0][0]*m0[1][5]+m2[2][8]*m1[1][8]*m0[0][0]+m2[2][8]*m1[1][6]*m0[0][3]+m2[2][8]*m1[1][3]*m0[0][6]+m2[2][8]*m1[1][0]*m0[0][8]-m2[2][8]*m1[0][8]*m0[1][0]-m2[2][8]*m1[0][6]*m0[1][3]-m2[2][8]*m1[0][3]*m0[1][6]-m2[2][8]*m1[0][0]*m0[1][8]+m2[2][6]*m1[1][8]*m0[0][3]+m2[2][6]*m1[1][6]*m0[0][5]+m2[2][6]*m1[1][5]*m0[0][6]+m2[2][6]*m1[1][3]*m0[0][8]-m2[2][6]*m1[0][8]*m0[1][3]-m2[2][6]*m1[0][6]*m0[1][5]-m2[2][6]*m1[0][5]*m0[1][6]-m2[2][6]*m1[0][3]*m0[1][8]+m2[2][5]*m1[1][9]*m0[0][0]+m2[2][5]*m1[1][6]*m0[0][6]+m2[2][5]*m1[1][0]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][0]-m2[2][5]*m1[0][6]*m0[1][6]-m2[2][5]*m1[0][0]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][3]+m2[2][3]*m1[1][8]*m0[0][6]+m2[2][3]*m1[1][6]*m0[0][8]+m2[2][3]*m1[1][3]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][3]-m2[2][3]*m1[0][8]*m0[1][6]-m2[2][3]*m1[0][6]*m0[1][8]-m2[2][3]*m1[0][3]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][5]+m2[2][0]*m1[1][8]*m0[0][8]+m2[2][0]*m1[1][5]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][5]-m2[2][0]*m1[0][8]*m0[1][8]-m2[2][0]*m1[0][5]*m0[1][9]-m2[1][9]*m1[2][5]*m0[0][0]-m2[1][9]*m1[2][3]*m0[0][3]-m2[1][9]*m1[2][0]*m0[0][5]+m2[1][9]*m1[0][5]*m0[2][0]+m2[1][9]*m1[0][3]*m0[2][3]+m2[1][9]*m1[0][0]*m0[2][5]-m2[1][8]*m1[2][8]*m0[0][0]-m2[1][8]*m1[2][6]*m0[0][3]-m2[1][8]*m1[2][3]*m0[0][6]-m2[1][8]*m1[2][0]*m0[0][8]+m2[1][8]*m1[0][8]*m0[2][0]+m2[1][8]*m1[0][6]*m0[2][3]+m2[1][8]*m1[0][3]*m0[2][6]+m2[1][8]*m1[0][0]*m0[2][8]-m2[1][6]*m1[2][8]*m0[0][3]-m2[1][6]*m1[2][6]*m0[0][5]-m2[1][6]*m1[2][5]*m0[0][6]-m2[1][6]*m1[2][3]*m0[0][8]+m2[1][6]*m1[0][8]*m0[2][3]+m2[1][6]*m1[0][6]*m0[2][5]+m2[1][6]*m1[0][5]*m0[2][6]+m2[1][6]*m1[0][3]*m0[2][8]-m2[1][5]*m1[2][9]*m0[0][0]-m2[1][5]*m1[2][6]*m0[0][6]-m2[1][5]*m1[2][0]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][0]+m2[1][5]*m1[0][6]*m0[2][6]+m2[1][5]*m1[0][0]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][3]-m2[1][3]*m1[2][8]*m0[0][6]-m2[1][3]*m1[2][6]*m0[0][8]-m2[1][3]*m1[2][3]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][3]+m2[1][3]*m1[0][8]*m0[2][6]+m2[1][3]*m1[0][6]*m0[2][8]+m2[1][3]*m1[0][3]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][5]-m2[1][0]*m1[2][8]*m0[0][8]-m2[1][0]*m1[2][5]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][5]+m2[1][0]*m1[0][8]*m0[2][8]+m2[1][0]*m1[0][5]*m0[2][9]+m2[0][9]*m1[2][5]*m0[1][0]+m2[0][9]*m1[2][3]*m0[1][3]+m2[0][9]*m1[2][0]*m0[1][5]-m2[0][9]*m1[1][5]*m0[2][0]-m2[0][9]*m1[1][3]*m0[2][3]-m2[0][9]*m1[1][0]*m0[2][5]+m2[0][8]*m1[2][8]*m0[1][0]+m2[0][8]*m1[2][6]*m0[1][3]+m2[0][8]*m1[2][3]*m0[1][6]+m2[0][8]*m1[2][0]*m0[1][8]-m2[0][8]*m1[1][8]*m0[2][0]-m2[0][8]*m1[1][6]*m0[2][3]-m2[0][8]*m1[1][3]*m0[2][6]-m2[0][8]*m1[1][0]*m0[2][8]+m2[0][6]*m1[2][8]*m0[1][3]+m2[0][6]*m1[2][6]*m0[1][5]+m2[0][6]*m1[2][5]*m0[1][6]+m2[0][6]*m1[2][3]*m0[1][8]-m2[0][6]*m1[1][8]*m0[2][3]-m2[0][6]*m1[1][6]*m0[2][5]-m2[0][6]*m1[1][5]*m0[2][6]-m2[0][6]*m1[1][3]*m0[2][8]+m2[0][5]*m1[2][9]*m0[1][0]+m2[0][5]*m1[2][6]*m0[1][6]+m2[0][5]*m1[2][0]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][0]-m2[0][5]*m1[1][6]*m0[2][6]-m2[0][5]*m1[1][0]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][3]+m2[0][3]*m1[2][8]*m0[1][6]+m2[0][3]*m1[2][6]*m0[1][8]+m2[0][3]*m1[2][3]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][3]-m2[0][3]*m1[1][8]*m0[2][6]-m2[0][3]*m1[1][6]*m0[2][8]-m2[0][3]*m1[1][3]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][5]+m2[0][0]*m1[2][8]*m0[1][8]+m2[0][0]*m1[2][5]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][5]-m2[0][0]*m1[1][8]*m0[2][8]-m2[0][0]*m1[1][5]*m0[2][9]; M1(row,59) = m2[2][9]*m1[1][5]*m0[0][1]+m2[2][9]*m1[1][4]*m0[0][3]+m2[2][9]*m1[1][3]*m0[0][4]+m2[2][9]*m1[1][1]*m0[0][5]-m2[2][9]*m1[0][5]*m0[1][1]-m2[2][9]*m1[0][4]*m0[1][3]-m2[2][9]*m1[0][3]*m0[1][4]-m2[2][9]*m1[0][1]*m0[1][5]+m2[2][8]*m1[1][8]*m0[0][1]+m2[2][8]*m1[1][7]*m0[0][3]+m2[2][8]*m1[1][6]*m0[0][4]+m2[2][8]*m1[1][4]*m0[0][6]+m2[2][8]*m1[1][3]*m0[0][7]+m2[2][8]*m1[1][1]*m0[0][8]-m2[2][8]*m1[0][8]*m0[1][1]-m2[2][8]*m1[0][7]*m0[1][3]-m2[2][8]*m1[0][6]*m0[1][4]-m2[2][8]*m1[0][4]*m0[1][6]-m2[2][8]*m1[0][3]*m0[1][7]-m2[2][8]*m1[0][1]*m0[1][8]+m2[2][7]*m1[1][8]*m0[0][3]+m2[2][7]*m1[1][6]*m0[0][5]+m2[2][7]*m1[1][5]*m0[0][6]+m2[2][7]*m1[1][3]*m0[0][8]-m2[2][7]*m1[0][8]*m0[1][3]-m2[2][7]*m1[0][6]*m0[1][5]-m2[2][7]*m1[0][5]*m0[1][6]-m2[2][7]*m1[0][3]*m0[1][8]+m2[2][6]*m1[1][8]*m0[0][4]+m2[2][6]*m1[1][7]*m0[0][5]+m2[2][6]*m1[1][5]*m0[0][7]+m2[2][6]*m1[1][4]*m0[0][8]-m2[2][6]*m1[0][8]*m0[1][4]-m2[2][6]*m1[0][7]*m0[1][5]-m2[2][6]*m1[0][5]*m0[1][7]-m2[2][6]*m1[0][4]*m0[1][8]+m2[2][5]*m1[1][9]*m0[0][1]+m2[2][5]*m1[1][7]*m0[0][6]+m2[2][5]*m1[1][6]*m0[0][7]+m2[2][5]*m1[1][1]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][1]-m2[2][5]*m1[0][7]*m0[1][6]-m2[2][5]*m1[0][6]*m0[1][7]-m2[2][5]*m1[0][1]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][3]+m2[2][4]*m1[1][8]*m0[0][6]+m2[2][4]*m1[1][6]*m0[0][8]+m2[2][4]*m1[1][3]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][3]-m2[2][4]*m1[0][8]*m0[1][6]-m2[2][4]*m1[0][6]*m0[1][8]-m2[2][4]*m1[0][3]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][4]+m2[2][3]*m1[1][8]*m0[0][7]+m2[2][3]*m1[1][7]*m0[0][8]+m2[2][3]*m1[1][4]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][4]-m2[2][3]*m1[0][8]*m0[1][7]-m2[2][3]*m1[0][7]*m0[1][8]-m2[2][3]*m1[0][4]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][5]+m2[2][1]*m1[1][8]*m0[0][8]+m2[2][1]*m1[1][5]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][5]-m2[2][1]*m1[0][8]*m0[1][8]-m2[2][1]*m1[0][5]*m0[1][9]-m2[1][9]*m1[2][5]*m0[0][1]-m2[1][9]*m1[2][4]*m0[0][3]-m2[1][9]*m1[2][3]*m0[0][4]-m2[1][9]*m1[2][1]*m0[0][5]+m2[1][9]*m1[0][5]*m0[2][1]+m2[1][9]*m1[0][4]*m0[2][3]+m2[1][9]*m1[0][3]*m0[2][4]+m2[1][9]*m1[0][1]*m0[2][5]-m2[1][8]*m1[2][8]*m0[0][1]-m2[1][8]*m1[2][7]*m0[0][3]-m2[1][8]*m1[2][6]*m0[0][4]-m2[1][8]*m1[2][4]*m0[0][6]-m2[1][8]*m1[2][3]*m0[0][7]-m2[1][8]*m1[2][1]*m0[0][8]+m2[1][8]*m1[0][8]*m0[2][1]+m2[1][8]*m1[0][7]*m0[2][3]+m2[1][8]*m1[0][6]*m0[2][4]+m2[1][8]*m1[0][4]*m0[2][6]+m2[1][8]*m1[0][3]*m0[2][7]+m2[1][8]*m1[0][1]*m0[2][8]-m2[1][7]*m1[2][8]*m0[0][3]-m2[1][7]*m1[2][6]*m0[0][5]-m2[1][7]*m1[2][5]*m0[0][6]-m2[1][7]*m1[2][3]*m0[0][8]+m2[1][7]*m1[0][8]*m0[2][3]+m2[1][7]*m1[0][6]*m0[2][5]+m2[1][7]*m1[0][5]*m0[2][6]+m2[1][7]*m1[0][3]*m0[2][8]-m2[1][6]*m1[2][8]*m0[0][4]-m2[1][6]*m1[2][7]*m0[0][5]-m2[1][6]*m1[2][5]*m0[0][7]-m2[1][6]*m1[2][4]*m0[0][8]+m2[1][6]*m1[0][8]*m0[2][4]+m2[1][6]*m1[0][7]*m0[2][5]+m2[1][6]*m1[0][5]*m0[2][7]+m2[1][6]*m1[0][4]*m0[2][8]-m2[1][5]*m1[2][9]*m0[0][1]-m2[1][5]*m1[2][7]*m0[0][6]-m2[1][5]*m1[2][6]*m0[0][7]-m2[1][5]*m1[2][1]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][1]+m2[1][5]*m1[0][7]*m0[2][6]+m2[1][5]*m1[0][6]*m0[2][7]+m2[1][5]*m1[0][1]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][3]-m2[1][4]*m1[2][8]*m0[0][6]-m2[1][4]*m1[2][6]*m0[0][8]-m2[1][4]*m1[2][3]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][3]+m2[1][4]*m1[0][8]*m0[2][6]+m2[1][4]*m1[0][6]*m0[2][8]+m2[1][4]*m1[0][3]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][4]-m2[1][3]*m1[2][8]*m0[0][7]-m2[1][3]*m1[2][7]*m0[0][8]-m2[1][3]*m1[2][4]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][4]+m2[1][3]*m1[0][8]*m0[2][7]+m2[1][3]*m1[0][7]*m0[2][8]+m2[1][3]*m1[0][4]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][5]-m2[1][1]*m1[2][8]*m0[0][8]-m2[1][1]*m1[2][5]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][5]+m2[1][1]*m1[0][8]*m0[2][8]+m2[1][1]*m1[0][5]*m0[2][9]+m2[0][9]*m1[2][5]*m0[1][1]+m2[0][9]*m1[2][4]*m0[1][3]+m2[0][9]*m1[2][3]*m0[1][4]+m2[0][9]*m1[2][1]*m0[1][5]-m2[0][9]*m1[1][5]*m0[2][1]-m2[0][9]*m1[1][4]*m0[2][3]-m2[0][9]*m1[1][3]*m0[2][4]-m2[0][9]*m1[1][1]*m0[2][5]+m2[0][8]*m1[2][8]*m0[1][1]+m2[0][8]*m1[2][7]*m0[1][3]+m2[0][8]*m1[2][6]*m0[1][4]+m2[0][8]*m1[2][4]*m0[1][6]+m2[0][8]*m1[2][3]*m0[1][7]+m2[0][8]*m1[2][1]*m0[1][8]-m2[0][8]*m1[1][8]*m0[2][1]-m2[0][8]*m1[1][7]*m0[2][3]-m2[0][8]*m1[1][6]*m0[2][4]-m2[0][8]*m1[1][4]*m0[2][6]-m2[0][8]*m1[1][3]*m0[2][7]-m2[0][8]*m1[1][1]*m0[2][8]+m2[0][7]*m1[2][8]*m0[1][3]+m2[0][7]*m1[2][6]*m0[1][5]+m2[0][7]*m1[2][5]*m0[1][6]+m2[0][7]*m1[2][3]*m0[1][8]-m2[0][7]*m1[1][8]*m0[2][3]-m2[0][7]*m1[1][6]*m0[2][5]-m2[0][7]*m1[1][5]*m0[2][6]-m2[0][7]*m1[1][3]*m0[2][8]+m2[0][6]*m1[2][8]*m0[1][4]+m2[0][6]*m1[2][7]*m0[1][5]+m2[0][6]*m1[2][5]*m0[1][7]+m2[0][6]*m1[2][4]*m0[1][8]-m2[0][6]*m1[1][8]*m0[2][4]-m2[0][6]*m1[1][7]*m0[2][5]-m2[0][6]*m1[1][5]*m0[2][7]-m2[0][6]*m1[1][4]*m0[2][8]+m2[0][5]*m1[2][9]*m0[1][1]+m2[0][5]*m1[2][7]*m0[1][6]+m2[0][5]*m1[2][6]*m0[1][7]+m2[0][5]*m1[2][1]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][1]-m2[0][5]*m1[1][7]*m0[2][6]-m2[0][5]*m1[1][6]*m0[2][7]-m2[0][5]*m1[1][1]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][3]+m2[0][4]*m1[2][8]*m0[1][6]+m2[0][4]*m1[2][6]*m0[1][8]+m2[0][4]*m1[2][3]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][3]-m2[0][4]*m1[1][8]*m0[2][6]-m2[0][4]*m1[1][6]*m0[2][8]-m2[0][4]*m1[1][3]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][4]+m2[0][3]*m1[2][8]*m0[1][7]+m2[0][3]*m1[2][7]*m0[1][8]+m2[0][3]*m1[2][4]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][4]-m2[0][3]*m1[1][8]*m0[2][7]-m2[0][3]*m1[1][7]*m0[2][8]-m2[0][3]*m1[1][4]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][5]+m2[0][1]*m1[2][8]*m0[1][8]+m2[0][1]*m1[2][5]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][5]-m2[0][1]*m1[1][8]*m0[2][8]-m2[0][1]*m1[1][5]*m0[2][9]; M1(row,60) = m2[2][9]*m1[1][5]*m0[0][2]+m2[2][9]*m1[1][4]*m0[0][4]+m2[2][9]*m1[1][2]*m0[0][5]-m2[2][9]*m1[0][5]*m0[1][2]-m2[2][9]*m1[0][4]*m0[1][4]-m2[2][9]*m1[0][2]*m0[1][5]+m2[2][8]*m1[1][8]*m0[0][2]+m2[2][8]*m1[1][7]*m0[0][4]+m2[2][8]*m1[1][4]*m0[0][7]+m2[2][8]*m1[1][2]*m0[0][8]-m2[2][8]*m1[0][8]*m0[1][2]-m2[2][8]*m1[0][7]*m0[1][4]-m2[2][8]*m1[0][4]*m0[1][7]-m2[2][8]*m1[0][2]*m0[1][8]+m2[2][7]*m1[1][8]*m0[0][4]+m2[2][7]*m1[1][7]*m0[0][5]+m2[2][7]*m1[1][5]*m0[0][7]+m2[2][7]*m1[1][4]*m0[0][8]-m2[2][7]*m1[0][8]*m0[1][4]-m2[2][7]*m1[0][7]*m0[1][5]-m2[2][7]*m1[0][5]*m0[1][7]-m2[2][7]*m1[0][4]*m0[1][8]+m2[2][5]*m1[1][9]*m0[0][2]+m2[2][5]*m1[1][7]*m0[0][7]+m2[2][5]*m1[1][2]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][2]-m2[2][5]*m1[0][7]*m0[1][7]-m2[2][5]*m1[0][2]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][4]+m2[2][4]*m1[1][8]*m0[0][7]+m2[2][4]*m1[1][7]*m0[0][8]+m2[2][4]*m1[1][4]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][4]-m2[2][4]*m1[0][8]*m0[1][7]-m2[2][4]*m1[0][7]*m0[1][8]-m2[2][4]*m1[0][4]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][5]+m2[2][2]*m1[1][8]*m0[0][8]+m2[2][2]*m1[1][5]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][5]-m2[2][2]*m1[0][8]*m0[1][8]-m2[2][2]*m1[0][5]*m0[1][9]-m2[1][9]*m1[2][5]*m0[0][2]-m2[1][9]*m1[2][4]*m0[0][4]-m2[1][9]*m1[2][2]*m0[0][5]+m2[1][9]*m1[0][5]*m0[2][2]+m2[1][9]*m1[0][4]*m0[2][4]+m2[1][9]*m1[0][2]*m0[2][5]-m2[1][8]*m1[2][8]*m0[0][2]-m2[1][8]*m1[2][7]*m0[0][4]-m2[1][8]*m1[2][4]*m0[0][7]-m2[1][8]*m1[2][2]*m0[0][8]+m2[1][8]*m1[0][8]*m0[2][2]+m2[1][8]*m1[0][7]*m0[2][4]+m2[1][8]*m1[0][4]*m0[2][7]+m2[1][8]*m1[0][2]*m0[2][8]-m2[1][7]*m1[2][8]*m0[0][4]-m2[1][7]*m1[2][7]*m0[0][5]-m2[1][7]*m1[2][5]*m0[0][7]-m2[1][7]*m1[2][4]*m0[0][8]+m2[1][7]*m1[0][8]*m0[2][4]+m2[1][7]*m1[0][7]*m0[2][5]+m2[1][7]*m1[0][5]*m0[2][7]+m2[1][7]*m1[0][4]*m0[2][8]-m2[1][5]*m1[2][9]*m0[0][2]-m2[1][5]*m1[2][7]*m0[0][7]-m2[1][5]*m1[2][2]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][2]+m2[1][5]*m1[0][7]*m0[2][7]+m2[1][5]*m1[0][2]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][4]-m2[1][4]*m1[2][8]*m0[0][7]-m2[1][4]*m1[2][7]*m0[0][8]-m2[1][4]*m1[2][4]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][4]+m2[1][4]*m1[0][8]*m0[2][7]+m2[1][4]*m1[0][7]*m0[2][8]+m2[1][4]*m1[0][4]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][5]-m2[1][2]*m1[2][8]*m0[0][8]-m2[1][2]*m1[2][5]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][5]+m2[1][2]*m1[0][8]*m0[2][8]+m2[1][2]*m1[0][5]*m0[2][9]+m2[0][9]*m1[2][5]*m0[1][2]+m2[0][9]*m1[2][4]*m0[1][4]+m2[0][9]*m1[2][2]*m0[1][5]-m2[0][9]*m1[1][5]*m0[2][2]-m2[0][9]*m1[1][4]*m0[2][4]-m2[0][9]*m1[1][2]*m0[2][5]+m2[0][8]*m1[2][8]*m0[1][2]+m2[0][8]*m1[2][7]*m0[1][4]+m2[0][8]*m1[2][4]*m0[1][7]+m2[0][8]*m1[2][2]*m0[1][8]-m2[0][8]*m1[1][8]*m0[2][2]-m2[0][8]*m1[1][7]*m0[2][4]-m2[0][8]*m1[1][4]*m0[2][7]-m2[0][8]*m1[1][2]*m0[2][8]+m2[0][7]*m1[2][8]*m0[1][4]+m2[0][7]*m1[2][7]*m0[1][5]+m2[0][7]*m1[2][5]*m0[1][7]+m2[0][7]*m1[2][4]*m0[1][8]-m2[0][7]*m1[1][8]*m0[2][4]-m2[0][7]*m1[1][7]*m0[2][5]-m2[0][7]*m1[1][5]*m0[2][7]-m2[0][7]*m1[1][4]*m0[2][8]+m2[0][5]*m1[2][9]*m0[1][2]+m2[0][5]*m1[2][7]*m0[1][7]+m2[0][5]*m1[2][2]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][2]-m2[0][5]*m1[1][7]*m0[2][7]-m2[0][5]*m1[1][2]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][4]+m2[0][4]*m1[2][8]*m0[1][7]+m2[0][4]*m1[2][7]*m0[1][8]+m2[0][4]*m1[2][4]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][4]-m2[0][4]*m1[1][8]*m0[2][7]-m2[0][4]*m1[1][7]*m0[2][8]-m2[0][4]*m1[1][4]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][5]+m2[0][2]*m1[2][8]*m0[1][8]+m2[0][2]*m1[2][5]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][5]-m2[0][2]*m1[1][8]*m0[2][8]-m2[0][2]*m1[1][5]*m0[2][9]; M1(row,61) = m2[2][9]*m1[1][5]*m0[0][3]+m2[2][9]*m1[1][3]*m0[0][5]-m2[2][9]*m1[0][5]*m0[1][3]-m2[2][9]*m1[0][3]*m0[1][5]+m2[2][8]*m1[1][8]*m0[0][3]+m2[2][8]*m1[1][6]*m0[0][5]+m2[2][8]*m1[1][5]*m0[0][6]+m2[2][8]*m1[1][3]*m0[0][8]-m2[2][8]*m1[0][8]*m0[1][3]-m2[2][8]*m1[0][6]*m0[1][5]-m2[2][8]*m1[0][5]*m0[1][6]-m2[2][8]*m1[0][3]*m0[1][8]+m2[2][6]*m1[1][8]*m0[0][5]+m2[2][6]*m1[1][5]*m0[0][8]-m2[2][6]*m1[0][8]*m0[1][5]-m2[2][6]*m1[0][5]*m0[1][8]+m2[2][5]*m1[1][9]*m0[0][3]+m2[2][5]*m1[1][8]*m0[0][6]+m2[2][5]*m1[1][6]*m0[0][8]+m2[2][5]*m1[1][3]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][3]-m2[2][5]*m1[0][8]*m0[1][6]-m2[2][5]*m1[0][6]*m0[1][8]-m2[2][5]*m1[0][3]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][5]+m2[2][3]*m1[1][8]*m0[0][8]+m2[2][3]*m1[1][5]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][5]-m2[2][3]*m1[0][8]*m0[1][8]-m2[2][3]*m1[0][5]*m0[1][9]-m2[1][9]*m1[2][5]*m0[0][3]-m2[1][9]*m1[2][3]*m0[0][5]+m2[1][9]*m1[0][5]*m0[2][3]+m2[1][9]*m1[0][3]*m0[2][5]-m2[1][8]*m1[2][8]*m0[0][3]-m2[1][8]*m1[2][6]*m0[0][5]-m2[1][8]*m1[2][5]*m0[0][6]-m2[1][8]*m1[2][3]*m0[0][8]+m2[1][8]*m1[0][8]*m0[2][3]+m2[1][8]*m1[0][6]*m0[2][5]+m2[1][8]*m1[0][5]*m0[2][6]+m2[1][8]*m1[0][3]*m0[2][8]-m2[1][6]*m1[2][8]*m0[0][5]-m2[1][6]*m1[2][5]*m0[0][8]+m2[1][6]*m1[0][8]*m0[2][5]+m2[1][6]*m1[0][5]*m0[2][8]-m2[1][5]*m1[2][9]*m0[0][3]-m2[1][5]*m1[2][8]*m0[0][6]-m2[1][5]*m1[2][6]*m0[0][8]-m2[1][5]*m1[2][3]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][3]+m2[1][5]*m1[0][8]*m0[2][6]+m2[1][5]*m1[0][6]*m0[2][8]+m2[1][5]*m1[0][3]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][5]-m2[1][3]*m1[2][8]*m0[0][8]-m2[1][3]*m1[2][5]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][5]+m2[1][3]*m1[0][8]*m0[2][8]+m2[1][3]*m1[0][5]*m0[2][9]+m2[0][9]*m1[2][5]*m0[1][3]+m2[0][9]*m1[2][3]*m0[1][5]-m2[0][9]*m1[1][5]*m0[2][3]-m2[0][9]*m1[1][3]*m0[2][5]+m2[0][8]*m1[2][8]*m0[1][3]+m2[0][8]*m1[2][6]*m0[1][5]+m2[0][8]*m1[2][5]*m0[1][6]+m2[0][8]*m1[2][3]*m0[1][8]-m2[0][8]*m1[1][8]*m0[2][3]-m2[0][8]*m1[1][6]*m0[2][5]-m2[0][8]*m1[1][5]*m0[2][6]-m2[0][8]*m1[1][3]*m0[2][8]+m2[0][6]*m1[2][8]*m0[1][5]+m2[0][6]*m1[2][5]*m0[1][8]-m2[0][6]*m1[1][8]*m0[2][5]-m2[0][6]*m1[1][5]*m0[2][8]+m2[0][5]*m1[2][9]*m0[1][3]+m2[0][5]*m1[2][8]*m0[1][6]+m2[0][5]*m1[2][6]*m0[1][8]+m2[0][5]*m1[2][3]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][3]-m2[0][5]*m1[1][8]*m0[2][6]-m2[0][5]*m1[1][6]*m0[2][8]-m2[0][5]*m1[1][3]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][5]+m2[0][3]*m1[2][8]*m0[1][8]+m2[0][3]*m1[2][5]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][5]-m2[0][3]*m1[1][8]*m0[2][8]-m2[0][3]*m1[1][5]*m0[2][9]; M1(row,62) = m2[2][9]*m1[1][5]*m0[0][4]+m2[2][9]*m1[1][4]*m0[0][5]-m2[2][9]*m1[0][5]*m0[1][4]-m2[2][9]*m1[0][4]*m0[1][5]+m2[2][8]*m1[1][8]*m0[0][4]+m2[2][8]*m1[1][7]*m0[0][5]+m2[2][8]*m1[1][5]*m0[0][7]+m2[2][8]*m1[1][4]*m0[0][8]-m2[2][8]*m1[0][8]*m0[1][4]-m2[2][8]*m1[0][7]*m0[1][5]-m2[2][8]*m1[0][5]*m0[1][7]-m2[2][8]*m1[0][4]*m0[1][8]+m2[2][7]*m1[1][8]*m0[0][5]+m2[2][7]*m1[1][5]*m0[0][8]-m2[2][7]*m1[0][8]*m0[1][5]-m2[2][7]*m1[0][5]*m0[1][8]+m2[2][5]*m1[1][9]*m0[0][4]+m2[2][5]*m1[1][8]*m0[0][7]+m2[2][5]*m1[1][7]*m0[0][8]+m2[2][5]*m1[1][4]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][4]-m2[2][5]*m1[0][8]*m0[1][7]-m2[2][5]*m1[0][7]*m0[1][8]-m2[2][5]*m1[0][4]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][5]+m2[2][4]*m1[1][8]*m0[0][8]+m2[2][4]*m1[1][5]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][5]-m2[2][4]*m1[0][8]*m0[1][8]-m2[2][4]*m1[0][5]*m0[1][9]-m2[1][9]*m1[2][5]*m0[0][4]-m2[1][9]*m1[2][4]*m0[0][5]+m2[1][9]*m1[0][5]*m0[2][4]+m2[1][9]*m1[0][4]*m0[2][5]-m2[1][8]*m1[2][8]*m0[0][4]-m2[1][8]*m1[2][7]*m0[0][5]-m2[1][8]*m1[2][5]*m0[0][7]-m2[1][8]*m1[2][4]*m0[0][8]+m2[1][8]*m1[0][8]*m0[2][4]+m2[1][8]*m1[0][7]*m0[2][5]+m2[1][8]*m1[0][5]*m0[2][7]+m2[1][8]*m1[0][4]*m0[2][8]-m2[1][7]*m1[2][8]*m0[0][5]-m2[1][7]*m1[2][5]*m0[0][8]+m2[1][7]*m1[0][8]*m0[2][5]+m2[1][7]*m1[0][5]*m0[2][8]-m2[1][5]*m1[2][9]*m0[0][4]-m2[1][5]*m1[2][8]*m0[0][7]-m2[1][5]*m1[2][7]*m0[0][8]-m2[1][5]*m1[2][4]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][4]+m2[1][5]*m1[0][8]*m0[2][7]+m2[1][5]*m1[0][7]*m0[2][8]+m2[1][5]*m1[0][4]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][5]-m2[1][4]*m1[2][8]*m0[0][8]-m2[1][4]*m1[2][5]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][5]+m2[1][4]*m1[0][8]*m0[2][8]+m2[1][4]*m1[0][5]*m0[2][9]+m2[0][9]*m1[2][5]*m0[1][4]+m2[0][9]*m1[2][4]*m0[1][5]-m2[0][9]*m1[1][5]*m0[2][4]-m2[0][9]*m1[1][4]*m0[2][5]+m2[0][8]*m1[2][8]*m0[1][4]+m2[0][8]*m1[2][7]*m0[1][5]+m2[0][8]*m1[2][5]*m0[1][7]+m2[0][8]*m1[2][4]*m0[1][8]-m2[0][8]*m1[1][8]*m0[2][4]-m2[0][8]*m1[1][7]*m0[2][5]-m2[0][8]*m1[1][5]*m0[2][7]-m2[0][8]*m1[1][4]*m0[2][8]+m2[0][7]*m1[2][8]*m0[1][5]+m2[0][7]*m1[2][5]*m0[1][8]-m2[0][7]*m1[1][8]*m0[2][5]-m2[0][7]*m1[1][5]*m0[2][8]+m2[0][5]*m1[2][9]*m0[1][4]+m2[0][5]*m1[2][8]*m0[1][7]+m2[0][5]*m1[2][7]*m0[1][8]+m2[0][5]*m1[2][4]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][4]-m2[0][5]*m1[1][8]*m0[2][7]-m2[0][5]*m1[1][7]*m0[2][8]-m2[0][5]*m1[1][4]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][5]+m2[0][4]*m1[2][8]*m0[1][8]+m2[0][4]*m1[2][5]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][5]-m2[0][4]*m1[1][8]*m0[2][8]-m2[0][4]*m1[1][5]*m0[2][9]; M1(row,63) = m2[2][9]*m1[1][5]*m0[0][5]-m2[2][9]*m1[0][5]*m0[1][5]+m2[2][8]*m1[1][8]*m0[0][5]+m2[2][8]*m1[1][5]*m0[0][8]-m2[2][8]*m1[0][8]*m0[1][5]-m2[2][8]*m1[0][5]*m0[1][8]+m2[2][5]*m1[1][9]*m0[0][5]+m2[2][5]*m1[1][8]*m0[0][8]+m2[2][5]*m1[1][5]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][5]-m2[2][5]*m1[0][8]*m0[1][8]-m2[2][5]*m1[0][5]*m0[1][9]-m2[1][9]*m1[2][5]*m0[0][5]+m2[1][9]*m1[0][5]*m0[2][5]-m2[1][8]*m1[2][8]*m0[0][5]-m2[1][8]*m1[2][5]*m0[0][8]+m2[1][8]*m1[0][8]*m0[2][5]+m2[1][8]*m1[0][5]*m0[2][8]-m2[1][5]*m1[2][9]*m0[0][5]-m2[1][5]*m1[2][8]*m0[0][8]-m2[1][5]*m1[2][5]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][5]+m2[1][5]*m1[0][8]*m0[2][8]+m2[1][5]*m1[0][5]*m0[2][9]+m2[0][9]*m1[2][5]*m0[1][5]-m2[0][9]*m1[1][5]*m0[2][5]+m2[0][8]*m1[2][8]*m0[1][5]+m2[0][8]*m1[2][5]*m0[1][8]-m2[0][8]*m1[1][8]*m0[2][5]-m2[0][8]*m1[1][5]*m0[2][8]+m2[0][5]*m1[2][9]*m0[1][5]+m2[0][5]*m1[2][8]*m0[1][8]+m2[0][5]*m1[2][5]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][5]-m2[0][5]*m1[1][8]*m0[2][8]-m2[0][5]*m1[1][5]*m0[2][9]; M1(row,64) = m2[2][9]*m1[1][6]*m0[0][0]+m2[2][9]*m1[1][0]*m0[0][6]-m2[2][9]*m1[0][6]*m0[1][0]-m2[2][9]*m1[0][0]*m0[1][6]+m2[2][6]*m1[1][9]*m0[0][0]+m2[2][6]*m1[1][6]*m0[0][6]+m2[2][6]*m1[1][0]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][0]-m2[2][6]*m1[0][6]*m0[1][6]-m2[2][6]*m1[0][0]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][6]+m2[2][0]*m1[1][6]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][6]-m2[2][0]*m1[0][6]*m0[1][9]-m2[1][9]*m1[2][6]*m0[0][0]-m2[1][9]*m1[2][0]*m0[0][6]+m2[1][9]*m1[0][6]*m0[2][0]+m2[1][9]*m1[0][0]*m0[2][6]-m2[1][6]*m1[2][9]*m0[0][0]-m2[1][6]*m1[2][6]*m0[0][6]-m2[1][6]*m1[2][0]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][0]+m2[1][6]*m1[0][6]*m0[2][6]+m2[1][6]*m1[0][0]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][6]-m2[1][0]*m1[2][6]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][6]+m2[1][0]*m1[0][6]*m0[2][9]+m2[0][9]*m1[2][6]*m0[1][0]+m2[0][9]*m1[2][0]*m0[1][6]-m2[0][9]*m1[1][6]*m0[2][0]-m2[0][9]*m1[1][0]*m0[2][6]+m2[0][6]*m1[2][9]*m0[1][0]+m2[0][6]*m1[2][6]*m0[1][6]+m2[0][6]*m1[2][0]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][0]-m2[0][6]*m1[1][6]*m0[2][6]-m2[0][6]*m1[1][0]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][6]+m2[0][0]*m1[2][6]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][6]-m2[0][0]*m1[1][6]*m0[2][9]; M1(row,65) = m2[2][9]*m1[1][7]*m0[0][0]+m2[2][9]*m1[1][6]*m0[0][1]+m2[2][9]*m1[1][1]*m0[0][6]+m2[2][9]*m1[1][0]*m0[0][7]-m2[2][9]*m1[0][7]*m0[1][0]-m2[2][9]*m1[0][6]*m0[1][1]-m2[2][9]*m1[0][1]*m0[1][6]-m2[2][9]*m1[0][0]*m0[1][7]+m2[2][7]*m1[1][9]*m0[0][0]+m2[2][7]*m1[1][6]*m0[0][6]+m2[2][7]*m1[1][0]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][0]-m2[2][7]*m1[0][6]*m0[1][6]-m2[2][7]*m1[0][0]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][1]+m2[2][6]*m1[1][7]*m0[0][6]+m2[2][6]*m1[1][6]*m0[0][7]+m2[2][6]*m1[1][1]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][1]-m2[2][6]*m1[0][7]*m0[1][6]-m2[2][6]*m1[0][6]*m0[1][7]-m2[2][6]*m1[0][1]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][6]+m2[2][1]*m1[1][6]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][6]-m2[2][1]*m1[0][6]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][7]+m2[2][0]*m1[1][7]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][7]-m2[2][0]*m1[0][7]*m0[1][9]-m2[1][9]*m1[2][7]*m0[0][0]-m2[1][9]*m1[2][6]*m0[0][1]-m2[1][9]*m1[2][1]*m0[0][6]-m2[1][9]*m1[2][0]*m0[0][7]+m2[1][9]*m1[0][7]*m0[2][0]+m2[1][9]*m1[0][6]*m0[2][1]+m2[1][9]*m1[0][1]*m0[2][6]+m2[1][9]*m1[0][0]*m0[2][7]-m2[1][7]*m1[2][9]*m0[0][0]-m2[1][7]*m1[2][6]*m0[0][6]-m2[1][7]*m1[2][0]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][0]+m2[1][7]*m1[0][6]*m0[2][6]+m2[1][7]*m1[0][0]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][1]-m2[1][6]*m1[2][7]*m0[0][6]-m2[1][6]*m1[2][6]*m0[0][7]-m2[1][6]*m1[2][1]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][1]+m2[1][6]*m1[0][7]*m0[2][6]+m2[1][6]*m1[0][6]*m0[2][7]+m2[1][6]*m1[0][1]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][6]-m2[1][1]*m1[2][6]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][6]+m2[1][1]*m1[0][6]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][7]-m2[1][0]*m1[2][7]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][7]+m2[1][0]*m1[0][7]*m0[2][9]+m2[0][9]*m1[2][7]*m0[1][0]+m2[0][9]*m1[2][6]*m0[1][1]+m2[0][9]*m1[2][1]*m0[1][6]+m2[0][9]*m1[2][0]*m0[1][7]-m2[0][9]*m1[1][7]*m0[2][0]-m2[0][9]*m1[1][6]*m0[2][1]-m2[0][9]*m1[1][1]*m0[2][6]-m2[0][9]*m1[1][0]*m0[2][7]+m2[0][7]*m1[2][9]*m0[1][0]+m2[0][7]*m1[2][6]*m0[1][6]+m2[0][7]*m1[2][0]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][0]-m2[0][7]*m1[1][6]*m0[2][6]-m2[0][7]*m1[1][0]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][1]+m2[0][6]*m1[2][7]*m0[1][6]+m2[0][6]*m1[2][6]*m0[1][7]+m2[0][6]*m1[2][1]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][1]-m2[0][6]*m1[1][7]*m0[2][6]-m2[0][6]*m1[1][6]*m0[2][7]-m2[0][6]*m1[1][1]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][6]+m2[0][1]*m1[2][6]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][6]-m2[0][1]*m1[1][6]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][7]+m2[0][0]*m1[2][7]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][7]-m2[0][0]*m1[1][7]*m0[2][9]; M1(row,66) = m2[2][9]*m1[1][7]*m0[0][1]+m2[2][9]*m1[1][6]*m0[0][2]+m2[2][9]*m1[1][2]*m0[0][6]+m2[2][9]*m1[1][1]*m0[0][7]-m2[2][9]*m1[0][7]*m0[1][1]-m2[2][9]*m1[0][6]*m0[1][2]-m2[2][9]*m1[0][2]*m0[1][6]-m2[2][9]*m1[0][1]*m0[1][7]+m2[2][7]*m1[1][9]*m0[0][1]+m2[2][7]*m1[1][7]*m0[0][6]+m2[2][7]*m1[1][6]*m0[0][7]+m2[2][7]*m1[1][1]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][1]-m2[2][7]*m1[0][7]*m0[1][6]-m2[2][7]*m1[0][6]*m0[1][7]-m2[2][7]*m1[0][1]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][2]+m2[2][6]*m1[1][7]*m0[0][7]+m2[2][6]*m1[1][2]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][2]-m2[2][6]*m1[0][7]*m0[1][7]-m2[2][6]*m1[0][2]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][6]+m2[2][2]*m1[1][6]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][6]-m2[2][2]*m1[0][6]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][7]+m2[2][1]*m1[1][7]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][7]-m2[2][1]*m1[0][7]*m0[1][9]-m2[1][9]*m1[2][7]*m0[0][1]-m2[1][9]*m1[2][6]*m0[0][2]-m2[1][9]*m1[2][2]*m0[0][6]-m2[1][9]*m1[2][1]*m0[0][7]+m2[1][9]*m1[0][7]*m0[2][1]+m2[1][9]*m1[0][6]*m0[2][2]+m2[1][9]*m1[0][2]*m0[2][6]+m2[1][9]*m1[0][1]*m0[2][7]-m2[1][7]*m1[2][9]*m0[0][1]-m2[1][7]*m1[2][7]*m0[0][6]-m2[1][7]*m1[2][6]*m0[0][7]-m2[1][7]*m1[2][1]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][1]+m2[1][7]*m1[0][7]*m0[2][6]+m2[1][7]*m1[0][6]*m0[2][7]+m2[1][7]*m1[0][1]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][2]-m2[1][6]*m1[2][7]*m0[0][7]-m2[1][6]*m1[2][2]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][2]+m2[1][6]*m1[0][7]*m0[2][7]+m2[1][6]*m1[0][2]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][6]-m2[1][2]*m1[2][6]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][6]+m2[1][2]*m1[0][6]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][7]-m2[1][1]*m1[2][7]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][7]+m2[1][1]*m1[0][7]*m0[2][9]+m2[0][9]*m1[2][7]*m0[1][1]+m2[0][9]*m1[2][6]*m0[1][2]+m2[0][9]*m1[2][2]*m0[1][6]+m2[0][9]*m1[2][1]*m0[1][7]-m2[0][9]*m1[1][7]*m0[2][1]-m2[0][9]*m1[1][6]*m0[2][2]-m2[0][9]*m1[1][2]*m0[2][6]-m2[0][9]*m1[1][1]*m0[2][7]+m2[0][7]*m1[2][9]*m0[1][1]+m2[0][7]*m1[2][7]*m0[1][6]+m2[0][7]*m1[2][6]*m0[1][7]+m2[0][7]*m1[2][1]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][1]-m2[0][7]*m1[1][7]*m0[2][6]-m2[0][7]*m1[1][6]*m0[2][7]-m2[0][7]*m1[1][1]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][2]+m2[0][6]*m1[2][7]*m0[1][7]+m2[0][6]*m1[2][2]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][2]-m2[0][6]*m1[1][7]*m0[2][7]-m2[0][6]*m1[1][2]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][6]+m2[0][2]*m1[2][6]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][6]-m2[0][2]*m1[1][6]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][7]+m2[0][1]*m1[2][7]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][7]-m2[0][1]*m1[1][7]*m0[2][9]; M1(row,67) = m2[2][9]*m1[1][7]*m0[0][2]+m2[2][9]*m1[1][2]*m0[0][7]-m2[2][9]*m1[0][7]*m0[1][2]-m2[2][9]*m1[0][2]*m0[1][7]+m2[2][7]*m1[1][9]*m0[0][2]+m2[2][7]*m1[1][7]*m0[0][7]+m2[2][7]*m1[1][2]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][2]-m2[2][7]*m1[0][7]*m0[1][7]-m2[2][7]*m1[0][2]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][7]+m2[2][2]*m1[1][7]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][7]-m2[2][2]*m1[0][7]*m0[1][9]-m2[1][9]*m1[2][7]*m0[0][2]-m2[1][9]*m1[2][2]*m0[0][7]+m2[1][9]*m1[0][7]*m0[2][2]+m2[1][9]*m1[0][2]*m0[2][7]-m2[1][7]*m1[2][9]*m0[0][2]-m2[1][7]*m1[2][7]*m0[0][7]-m2[1][7]*m1[2][2]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][2]+m2[1][7]*m1[0][7]*m0[2][7]+m2[1][7]*m1[0][2]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][7]-m2[1][2]*m1[2][7]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][7]+m2[1][2]*m1[0][7]*m0[2][9]+m2[0][9]*m1[2][7]*m0[1][2]+m2[0][9]*m1[2][2]*m0[1][7]-m2[0][9]*m1[1][7]*m0[2][2]-m2[0][9]*m1[1][2]*m0[2][7]+m2[0][7]*m1[2][9]*m0[1][2]+m2[0][7]*m1[2][7]*m0[1][7]+m2[0][7]*m1[2][2]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][2]-m2[0][7]*m1[1][7]*m0[2][7]-m2[0][7]*m1[1][2]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][7]+m2[0][2]*m1[2][7]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][7]-m2[0][2]*m1[1][7]*m0[2][9]; M1(row,68) = m2[2][9]*m1[1][8]*m0[0][0]+m2[2][9]*m1[1][6]*m0[0][3]+m2[2][9]*m1[1][3]*m0[0][6]+m2[2][9]*m1[1][0]*m0[0][8]-m2[2][9]*m1[0][8]*m0[1][0]-m2[2][9]*m1[0][6]*m0[1][3]-m2[2][9]*m1[0][3]*m0[1][6]-m2[2][9]*m1[0][0]*m0[1][8]+m2[2][8]*m1[1][9]*m0[0][0]+m2[2][8]*m1[1][6]*m0[0][6]+m2[2][8]*m1[1][0]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][0]-m2[2][8]*m1[0][6]*m0[1][6]-m2[2][8]*m1[0][0]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][3]+m2[2][6]*m1[1][8]*m0[0][6]+m2[2][6]*m1[1][6]*m0[0][8]+m2[2][6]*m1[1][3]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][3]-m2[2][6]*m1[0][8]*m0[1][6]-m2[2][6]*m1[0][6]*m0[1][8]-m2[2][6]*m1[0][3]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][6]+m2[2][3]*m1[1][6]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][6]-m2[2][3]*m1[0][6]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][8]+m2[2][0]*m1[1][8]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][8]-m2[2][0]*m1[0][8]*m0[1][9]-m2[1][9]*m1[2][8]*m0[0][0]-m2[1][9]*m1[2][6]*m0[0][3]-m2[1][9]*m1[2][3]*m0[0][6]-m2[1][9]*m1[2][0]*m0[0][8]+m2[1][9]*m1[0][8]*m0[2][0]+m2[1][9]*m1[0][6]*m0[2][3]+m2[1][9]*m1[0][3]*m0[2][6]+m2[1][9]*m1[0][0]*m0[2][8]-m2[1][8]*m1[2][9]*m0[0][0]-m2[1][8]*m1[2][6]*m0[0][6]-m2[1][8]*m1[2][0]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][0]+m2[1][8]*m1[0][6]*m0[2][6]+m2[1][8]*m1[0][0]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][3]-m2[1][6]*m1[2][8]*m0[0][6]-m2[1][6]*m1[2][6]*m0[0][8]-m2[1][6]*m1[2][3]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][3]+m2[1][6]*m1[0][8]*m0[2][6]+m2[1][6]*m1[0][6]*m0[2][8]+m2[1][6]*m1[0][3]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][6]-m2[1][3]*m1[2][6]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][6]+m2[1][3]*m1[0][6]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][8]-m2[1][0]*m1[2][8]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][8]+m2[1][0]*m1[0][8]*m0[2][9]+m2[0][9]*m1[2][8]*m0[1][0]+m2[0][9]*m1[2][6]*m0[1][3]+m2[0][9]*m1[2][3]*m0[1][6]+m2[0][9]*m1[2][0]*m0[1][8]-m2[0][9]*m1[1][8]*m0[2][0]-m2[0][9]*m1[1][6]*m0[2][3]-m2[0][9]*m1[1][3]*m0[2][6]-m2[0][9]*m1[1][0]*m0[2][8]+m2[0][8]*m1[2][9]*m0[1][0]+m2[0][8]*m1[2][6]*m0[1][6]+m2[0][8]*m1[2][0]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][0]-m2[0][8]*m1[1][6]*m0[2][6]-m2[0][8]*m1[1][0]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][3]+m2[0][6]*m1[2][8]*m0[1][6]+m2[0][6]*m1[2][6]*m0[1][8]+m2[0][6]*m1[2][3]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][3]-m2[0][6]*m1[1][8]*m0[2][6]-m2[0][6]*m1[1][6]*m0[2][8]-m2[0][6]*m1[1][3]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][6]+m2[0][3]*m1[2][6]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][6]-m2[0][3]*m1[1][6]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][8]+m2[0][0]*m1[2][8]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][8]-m2[0][0]*m1[1][8]*m0[2][9]; M1(row,69) = m2[2][9]*m1[1][8]*m0[0][1]+m2[2][9]*m1[1][7]*m0[0][3]+m2[2][9]*m1[1][6]*m0[0][4]+m2[2][9]*m1[1][4]*m0[0][6]+m2[2][9]*m1[1][3]*m0[0][7]+m2[2][9]*m1[1][1]*m0[0][8]-m2[2][9]*m1[0][8]*m0[1][1]-m2[2][9]*m1[0][7]*m0[1][3]-m2[2][9]*m1[0][6]*m0[1][4]-m2[2][9]*m1[0][4]*m0[1][6]-m2[2][9]*m1[0][3]*m0[1][7]-m2[2][9]*m1[0][1]*m0[1][8]+m2[2][8]*m1[1][9]*m0[0][1]+m2[2][8]*m1[1][7]*m0[0][6]+m2[2][8]*m1[1][6]*m0[0][7]+m2[2][8]*m1[1][1]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][1]-m2[2][8]*m1[0][7]*m0[1][6]-m2[2][8]*m1[0][6]*m0[1][7]-m2[2][8]*m1[0][1]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][3]+m2[2][7]*m1[1][8]*m0[0][6]+m2[2][7]*m1[1][6]*m0[0][8]+m2[2][7]*m1[1][3]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][3]-m2[2][7]*m1[0][8]*m0[1][6]-m2[2][7]*m1[0][6]*m0[1][8]-m2[2][7]*m1[0][3]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][4]+m2[2][6]*m1[1][8]*m0[0][7]+m2[2][6]*m1[1][7]*m0[0][8]+m2[2][6]*m1[1][4]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][4]-m2[2][6]*m1[0][8]*m0[1][7]-m2[2][6]*m1[0][7]*m0[1][8]-m2[2][6]*m1[0][4]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][6]+m2[2][4]*m1[1][6]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][6]-m2[2][4]*m1[0][6]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][7]+m2[2][3]*m1[1][7]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][7]-m2[2][3]*m1[0][7]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][8]+m2[2][1]*m1[1][8]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][8]-m2[2][1]*m1[0][8]*m0[1][9]-m2[1][9]*m1[2][8]*m0[0][1]-m2[1][9]*m1[2][7]*m0[0][3]-m2[1][9]*m1[2][6]*m0[0][4]-m2[1][9]*m1[2][4]*m0[0][6]-m2[1][9]*m1[2][3]*m0[0][7]-m2[1][9]*m1[2][1]*m0[0][8]+m2[1][9]*m1[0][8]*m0[2][1]+m2[1][9]*m1[0][7]*m0[2][3]+m2[1][9]*m1[0][6]*m0[2][4]+m2[1][9]*m1[0][4]*m0[2][6]+m2[1][9]*m1[0][3]*m0[2][7]+m2[1][9]*m1[0][1]*m0[2][8]-m2[1][8]*m1[2][9]*m0[0][1]-m2[1][8]*m1[2][7]*m0[0][6]-m2[1][8]*m1[2][6]*m0[0][7]-m2[1][8]*m1[2][1]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][1]+m2[1][8]*m1[0][7]*m0[2][6]+m2[1][8]*m1[0][6]*m0[2][7]+m2[1][8]*m1[0][1]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][3]-m2[1][7]*m1[2][8]*m0[0][6]-m2[1][7]*m1[2][6]*m0[0][8]-m2[1][7]*m1[2][3]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][3]+m2[1][7]*m1[0][8]*m0[2][6]+m2[1][7]*m1[0][6]*m0[2][8]+m2[1][7]*m1[0][3]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][4]-m2[1][6]*m1[2][8]*m0[0][7]-m2[1][6]*m1[2][7]*m0[0][8]-m2[1][6]*m1[2][4]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][4]+m2[1][6]*m1[0][8]*m0[2][7]+m2[1][6]*m1[0][7]*m0[2][8]+m2[1][6]*m1[0][4]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][6]-m2[1][4]*m1[2][6]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][6]+m2[1][4]*m1[0][6]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][7]-m2[1][3]*m1[2][7]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][7]+m2[1][3]*m1[0][7]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][8]-m2[1][1]*m1[2][8]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][8]+m2[1][1]*m1[0][8]*m0[2][9]+m2[0][9]*m1[2][8]*m0[1][1]+m2[0][9]*m1[2][7]*m0[1][3]+m2[0][9]*m1[2][6]*m0[1][4]+m2[0][9]*m1[2][4]*m0[1][6]+m2[0][9]*m1[2][3]*m0[1][7]+m2[0][9]*m1[2][1]*m0[1][8]-m2[0][9]*m1[1][8]*m0[2][1]-m2[0][9]*m1[1][7]*m0[2][3]-m2[0][9]*m1[1][6]*m0[2][4]-m2[0][9]*m1[1][4]*m0[2][6]-m2[0][9]*m1[1][3]*m0[2][7]-m2[0][9]*m1[1][1]*m0[2][8]+m2[0][8]*m1[2][9]*m0[1][1]+m2[0][8]*m1[2][7]*m0[1][6]+m2[0][8]*m1[2][6]*m0[1][7]+m2[0][8]*m1[2][1]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][1]-m2[0][8]*m1[1][7]*m0[2][6]-m2[0][8]*m1[1][6]*m0[2][7]-m2[0][8]*m1[1][1]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][3]+m2[0][7]*m1[2][8]*m0[1][6]+m2[0][7]*m1[2][6]*m0[1][8]+m2[0][7]*m1[2][3]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][3]-m2[0][7]*m1[1][8]*m0[2][6]-m2[0][7]*m1[1][6]*m0[2][8]-m2[0][7]*m1[1][3]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][4]+m2[0][6]*m1[2][8]*m0[1][7]+m2[0][6]*m1[2][7]*m0[1][8]+m2[0][6]*m1[2][4]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][4]-m2[0][6]*m1[1][8]*m0[2][7]-m2[0][6]*m1[1][7]*m0[2][8]-m2[0][6]*m1[1][4]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][6]+m2[0][4]*m1[2][6]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][6]-m2[0][4]*m1[1][6]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][7]+m2[0][3]*m1[2][7]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][7]-m2[0][3]*m1[1][7]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][8]+m2[0][1]*m1[2][8]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][8]-m2[0][1]*m1[1][8]*m0[2][9]; M1(row,70) = m2[2][9]*m1[1][8]*m0[0][2]+m2[2][9]*m1[1][7]*m0[0][4]+m2[2][9]*m1[1][4]*m0[0][7]+m2[2][9]*m1[1][2]*m0[0][8]-m2[2][9]*m1[0][8]*m0[1][2]-m2[2][9]*m1[0][7]*m0[1][4]-m2[2][9]*m1[0][4]*m0[1][7]-m2[2][9]*m1[0][2]*m0[1][8]+m2[2][8]*m1[1][9]*m0[0][2]+m2[2][8]*m1[1][7]*m0[0][7]+m2[2][8]*m1[1][2]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][2]-m2[2][8]*m1[0][7]*m0[1][7]-m2[2][8]*m1[0][2]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][4]+m2[2][7]*m1[1][8]*m0[0][7]+m2[2][7]*m1[1][7]*m0[0][8]+m2[2][7]*m1[1][4]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][4]-m2[2][7]*m1[0][8]*m0[1][7]-m2[2][7]*m1[0][7]*m0[1][8]-m2[2][7]*m1[0][4]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][7]+m2[2][4]*m1[1][7]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][7]-m2[2][4]*m1[0][7]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][8]+m2[2][2]*m1[1][8]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][8]-m2[2][2]*m1[0][8]*m0[1][9]-m2[1][9]*m1[2][8]*m0[0][2]-m2[1][9]*m1[2][7]*m0[0][4]-m2[1][9]*m1[2][4]*m0[0][7]-m2[1][9]*m1[2][2]*m0[0][8]+m2[1][9]*m1[0][8]*m0[2][2]+m2[1][9]*m1[0][7]*m0[2][4]+m2[1][9]*m1[0][4]*m0[2][7]+m2[1][9]*m1[0][2]*m0[2][8]-m2[1][8]*m1[2][9]*m0[0][2]-m2[1][8]*m1[2][7]*m0[0][7]-m2[1][8]*m1[2][2]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][2]+m2[1][8]*m1[0][7]*m0[2][7]+m2[1][8]*m1[0][2]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][4]-m2[1][7]*m1[2][8]*m0[0][7]-m2[1][7]*m1[2][7]*m0[0][8]-m2[1][7]*m1[2][4]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][4]+m2[1][7]*m1[0][8]*m0[2][7]+m2[1][7]*m1[0][7]*m0[2][8]+m2[1][7]*m1[0][4]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][7]-m2[1][4]*m1[2][7]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][7]+m2[1][4]*m1[0][7]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][8]-m2[1][2]*m1[2][8]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][8]+m2[1][2]*m1[0][8]*m0[2][9]+m2[0][9]*m1[2][8]*m0[1][2]+m2[0][9]*m1[2][7]*m0[1][4]+m2[0][9]*m1[2][4]*m0[1][7]+m2[0][9]*m1[2][2]*m0[1][8]-m2[0][9]*m1[1][8]*m0[2][2]-m2[0][9]*m1[1][7]*m0[2][4]-m2[0][9]*m1[1][4]*m0[2][7]-m2[0][9]*m1[1][2]*m0[2][8]+m2[0][8]*m1[2][9]*m0[1][2]+m2[0][8]*m1[2][7]*m0[1][7]+m2[0][8]*m1[2][2]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][2]-m2[0][8]*m1[1][7]*m0[2][7]-m2[0][8]*m1[1][2]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][4]+m2[0][7]*m1[2][8]*m0[1][7]+m2[0][7]*m1[2][7]*m0[1][8]+m2[0][7]*m1[2][4]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][4]-m2[0][7]*m1[1][8]*m0[2][7]-m2[0][7]*m1[1][7]*m0[2][8]-m2[0][7]*m1[1][4]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][7]+m2[0][4]*m1[2][7]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][7]-m2[0][4]*m1[1][7]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][8]+m2[0][2]*m1[2][8]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][8]-m2[0][2]*m1[1][8]*m0[2][9]; M1(row,71) = m2[2][9]*m1[1][8]*m0[0][3]+m2[2][9]*m1[1][6]*m0[0][5]+m2[2][9]*m1[1][5]*m0[0][6]+m2[2][9]*m1[1][3]*m0[0][8]-m2[2][9]*m1[0][8]*m0[1][3]-m2[2][9]*m1[0][6]*m0[1][5]-m2[2][9]*m1[0][5]*m0[1][6]-m2[2][9]*m1[0][3]*m0[1][8]+m2[2][8]*m1[1][9]*m0[0][3]+m2[2][8]*m1[1][8]*m0[0][6]+m2[2][8]*m1[1][6]*m0[0][8]+m2[2][8]*m1[1][3]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][3]-m2[2][8]*m1[0][8]*m0[1][6]-m2[2][8]*m1[0][6]*m0[1][8]-m2[2][8]*m1[0][3]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][5]+m2[2][6]*m1[1][8]*m0[0][8]+m2[2][6]*m1[1][5]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][5]-m2[2][6]*m1[0][8]*m0[1][8]-m2[2][6]*m1[0][5]*m0[1][9]+m2[2][5]*m1[1][9]*m0[0][6]+m2[2][5]*m1[1][6]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][6]-m2[2][5]*m1[0][6]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][8]+m2[2][3]*m1[1][8]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][8]-m2[2][3]*m1[0][8]*m0[1][9]-m2[1][9]*m1[2][8]*m0[0][3]-m2[1][9]*m1[2][6]*m0[0][5]-m2[1][9]*m1[2][5]*m0[0][6]-m2[1][9]*m1[2][3]*m0[0][8]+m2[1][9]*m1[0][8]*m0[2][3]+m2[1][9]*m1[0][6]*m0[2][5]+m2[1][9]*m1[0][5]*m0[2][6]+m2[1][9]*m1[0][3]*m0[2][8]-m2[1][8]*m1[2][9]*m0[0][3]-m2[1][8]*m1[2][8]*m0[0][6]-m2[1][8]*m1[2][6]*m0[0][8]-m2[1][8]*m1[2][3]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][3]+m2[1][8]*m1[0][8]*m0[2][6]+m2[1][8]*m1[0][6]*m0[2][8]+m2[1][8]*m1[0][3]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][5]-m2[1][6]*m1[2][8]*m0[0][8]-m2[1][6]*m1[2][5]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][5]+m2[1][6]*m1[0][8]*m0[2][8]+m2[1][6]*m1[0][5]*m0[2][9]-m2[1][5]*m1[2][9]*m0[0][6]-m2[1][5]*m1[2][6]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][6]+m2[1][5]*m1[0][6]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][8]-m2[1][3]*m1[2][8]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][8]+m2[1][3]*m1[0][8]*m0[2][9]+m2[0][9]*m1[2][8]*m0[1][3]+m2[0][9]*m1[2][6]*m0[1][5]+m2[0][9]*m1[2][5]*m0[1][6]+m2[0][9]*m1[2][3]*m0[1][8]-m2[0][9]*m1[1][8]*m0[2][3]-m2[0][9]*m1[1][6]*m0[2][5]-m2[0][9]*m1[1][5]*m0[2][6]-m2[0][9]*m1[1][3]*m0[2][8]+m2[0][8]*m1[2][9]*m0[1][3]+m2[0][8]*m1[2][8]*m0[1][6]+m2[0][8]*m1[2][6]*m0[1][8]+m2[0][8]*m1[2][3]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][3]-m2[0][8]*m1[1][8]*m0[2][6]-m2[0][8]*m1[1][6]*m0[2][8]-m2[0][8]*m1[1][3]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][5]+m2[0][6]*m1[2][8]*m0[1][8]+m2[0][6]*m1[2][5]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][5]-m2[0][6]*m1[1][8]*m0[2][8]-m2[0][6]*m1[1][5]*m0[2][9]+m2[0][5]*m1[2][9]*m0[1][6]+m2[0][5]*m1[2][6]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][6]-m2[0][5]*m1[1][6]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][8]+m2[0][3]*m1[2][8]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][8]-m2[0][3]*m1[1][8]*m0[2][9]; M1(row,72) = m2[2][9]*m1[1][8]*m0[0][4]+m2[2][9]*m1[1][7]*m0[0][5]+m2[2][9]*m1[1][5]*m0[0][7]+m2[2][9]*m1[1][4]*m0[0][8]-m2[2][9]*m1[0][8]*m0[1][4]-m2[2][9]*m1[0][7]*m0[1][5]-m2[2][9]*m1[0][5]*m0[1][7]-m2[2][9]*m1[0][4]*m0[1][8]+m2[2][8]*m1[1][9]*m0[0][4]+m2[2][8]*m1[1][8]*m0[0][7]+m2[2][8]*m1[1][7]*m0[0][8]+m2[2][8]*m1[1][4]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][4]-m2[2][8]*m1[0][8]*m0[1][7]-m2[2][8]*m1[0][7]*m0[1][8]-m2[2][8]*m1[0][4]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][5]+m2[2][7]*m1[1][8]*m0[0][8]+m2[2][7]*m1[1][5]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][5]-m2[2][7]*m1[0][8]*m0[1][8]-m2[2][7]*m1[0][5]*m0[1][9]+m2[2][5]*m1[1][9]*m0[0][7]+m2[2][5]*m1[1][7]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][7]-m2[2][5]*m1[0][7]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][8]+m2[2][4]*m1[1][8]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][8]-m2[2][4]*m1[0][8]*m0[1][9]-m2[1][9]*m1[2][8]*m0[0][4]-m2[1][9]*m1[2][7]*m0[0][5]-m2[1][9]*m1[2][5]*m0[0][7]-m2[1][9]*m1[2][4]*m0[0][8]+m2[1][9]*m1[0][8]*m0[2][4]+m2[1][9]*m1[0][7]*m0[2][5]+m2[1][9]*m1[0][5]*m0[2][7]+m2[1][9]*m1[0][4]*m0[2][8]-m2[1][8]*m1[2][9]*m0[0][4]-m2[1][8]*m1[2][8]*m0[0][7]-m2[1][8]*m1[2][7]*m0[0][8]-m2[1][8]*m1[2][4]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][4]+m2[1][8]*m1[0][8]*m0[2][7]+m2[1][8]*m1[0][7]*m0[2][8]+m2[1][8]*m1[0][4]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][5]-m2[1][7]*m1[2][8]*m0[0][8]-m2[1][7]*m1[2][5]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][5]+m2[1][7]*m1[0][8]*m0[2][8]+m2[1][7]*m1[0][5]*m0[2][9]-m2[1][5]*m1[2][9]*m0[0][7]-m2[1][5]*m1[2][7]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][7]+m2[1][5]*m1[0][7]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][8]-m2[1][4]*m1[2][8]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][8]+m2[1][4]*m1[0][8]*m0[2][9]+m2[0][9]*m1[2][8]*m0[1][4]+m2[0][9]*m1[2][7]*m0[1][5]+m2[0][9]*m1[2][5]*m0[1][7]+m2[0][9]*m1[2][4]*m0[1][8]-m2[0][9]*m1[1][8]*m0[2][4]-m2[0][9]*m1[1][7]*m0[2][5]-m2[0][9]*m1[1][5]*m0[2][7]-m2[0][9]*m1[1][4]*m0[2][8]+m2[0][8]*m1[2][9]*m0[1][4]+m2[0][8]*m1[2][8]*m0[1][7]+m2[0][8]*m1[2][7]*m0[1][8]+m2[0][8]*m1[2][4]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][4]-m2[0][8]*m1[1][8]*m0[2][7]-m2[0][8]*m1[1][7]*m0[2][8]-m2[0][8]*m1[1][4]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][5]+m2[0][7]*m1[2][8]*m0[1][8]+m2[0][7]*m1[2][5]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][5]-m2[0][7]*m1[1][8]*m0[2][8]-m2[0][7]*m1[1][5]*m0[2][9]+m2[0][5]*m1[2][9]*m0[1][7]+m2[0][5]*m1[2][7]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][7]-m2[0][5]*m1[1][7]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][8]+m2[0][4]*m1[2][8]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][8]-m2[0][4]*m1[1][8]*m0[2][9]; M1(row,73) = m2[2][9]*m1[1][8]*m0[0][5]+m2[2][9]*m1[1][5]*m0[0][8]-m2[2][9]*m1[0][8]*m0[1][5]-m2[2][9]*m1[0][5]*m0[1][8]+m2[2][8]*m1[1][9]*m0[0][5]+m2[2][8]*m1[1][8]*m0[0][8]+m2[2][8]*m1[1][5]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][5]-m2[2][8]*m1[0][8]*m0[1][8]-m2[2][8]*m1[0][5]*m0[1][9]+m2[2][5]*m1[1][9]*m0[0][8]+m2[2][5]*m1[1][8]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][8]-m2[2][5]*m1[0][8]*m0[1][9]-m2[1][9]*m1[2][8]*m0[0][5]-m2[1][9]*m1[2][5]*m0[0][8]+m2[1][9]*m1[0][8]*m0[2][5]+m2[1][9]*m1[0][5]*m0[2][8]-m2[1][8]*m1[2][9]*m0[0][5]-m2[1][8]*m1[2][8]*m0[0][8]-m2[1][8]*m1[2][5]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][5]+m2[1][8]*m1[0][8]*m0[2][8]+m2[1][8]*m1[0][5]*m0[2][9]-m2[1][5]*m1[2][9]*m0[0][8]-m2[1][5]*m1[2][8]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][8]+m2[1][5]*m1[0][8]*m0[2][9]+m2[0][9]*m1[2][8]*m0[1][5]+m2[0][9]*m1[2][5]*m0[1][8]-m2[0][9]*m1[1][8]*m0[2][5]-m2[0][9]*m1[1][5]*m0[2][8]+m2[0][8]*m1[2][9]*m0[1][5]+m2[0][8]*m1[2][8]*m0[1][8]+m2[0][8]*m1[2][5]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][5]-m2[0][8]*m1[1][8]*m0[2][8]-m2[0][8]*m1[1][5]*m0[2][9]+m2[0][5]*m1[2][9]*m0[1][8]+m2[0][5]*m1[2][8]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][8]-m2[0][5]*m1[1][8]*m0[2][9]; M1(row,74) = m2[2][9]*m1[1][9]*m0[0][0]+m2[2][9]*m1[1][6]*m0[0][6]+m2[2][9]*m1[1][0]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][0]-m2[2][9]*m1[0][6]*m0[1][6]-m2[2][9]*m1[0][0]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][6]+m2[2][6]*m1[1][6]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][6]-m2[2][6]*m1[0][6]*m0[1][9]+m2[2][0]*m1[1][9]*m0[0][9]-m2[2][0]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][0]-m2[1][9]*m1[2][6]*m0[0][6]-m2[1][9]*m1[2][0]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][0]+m2[1][9]*m1[0][6]*m0[2][6]+m2[1][9]*m1[0][0]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][6]-m2[1][6]*m1[2][6]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][6]+m2[1][6]*m1[0][6]*m0[2][9]-m2[1][0]*m1[2][9]*m0[0][9]+m2[1][0]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][0]+m2[0][9]*m1[2][6]*m0[1][6]+m2[0][9]*m1[2][0]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][0]-m2[0][9]*m1[1][6]*m0[2][6]-m2[0][9]*m1[1][0]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][6]+m2[0][6]*m1[2][6]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][6]-m2[0][6]*m1[1][6]*m0[2][9]+m2[0][0]*m1[2][9]*m0[1][9]-m2[0][0]*m1[1][9]*m0[2][9]; M1(row,75) = m2[2][9]*m1[1][9]*m0[0][1]+m2[2][9]*m1[1][7]*m0[0][6]+m2[2][9]*m1[1][6]*m0[0][7]+m2[2][9]*m1[1][1]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][1]-m2[2][9]*m1[0][7]*m0[1][6]-m2[2][9]*m1[0][6]*m0[1][7]-m2[2][9]*m1[0][1]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][6]+m2[2][7]*m1[1][6]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][6]-m2[2][7]*m1[0][6]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][7]+m2[2][6]*m1[1][7]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][7]-m2[2][6]*m1[0][7]*m0[1][9]+m2[2][1]*m1[1][9]*m0[0][9]-m2[2][1]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][1]-m2[1][9]*m1[2][7]*m0[0][6]-m2[1][9]*m1[2][6]*m0[0][7]-m2[1][9]*m1[2][1]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][1]+m2[1][9]*m1[0][7]*m0[2][6]+m2[1][9]*m1[0][6]*m0[2][7]+m2[1][9]*m1[0][1]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][6]-m2[1][7]*m1[2][6]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][6]+m2[1][7]*m1[0][6]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][7]-m2[1][6]*m1[2][7]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][7]+m2[1][6]*m1[0][7]*m0[2][9]-m2[1][1]*m1[2][9]*m0[0][9]+m2[1][1]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][1]+m2[0][9]*m1[2][7]*m0[1][6]+m2[0][9]*m1[2][6]*m0[1][7]+m2[0][9]*m1[2][1]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][1]-m2[0][9]*m1[1][7]*m0[2][6]-m2[0][9]*m1[1][6]*m0[2][7]-m2[0][9]*m1[1][1]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][6]+m2[0][7]*m1[2][6]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][6]-m2[0][7]*m1[1][6]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][7]+m2[0][6]*m1[2][7]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][7]-m2[0][6]*m1[1][7]*m0[2][9]+m2[0][1]*m1[2][9]*m0[1][9]-m2[0][1]*m1[1][9]*m0[2][9]; M1(row,76) = m2[2][9]*m1[1][9]*m0[0][2]+m2[2][9]*m1[1][7]*m0[0][7]+m2[2][9]*m1[1][2]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][2]-m2[2][9]*m1[0][7]*m0[1][7]-m2[2][9]*m1[0][2]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][7]+m2[2][7]*m1[1][7]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][7]-m2[2][7]*m1[0][7]*m0[1][9]+m2[2][2]*m1[1][9]*m0[0][9]-m2[2][2]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][2]-m2[1][9]*m1[2][7]*m0[0][7]-m2[1][9]*m1[2][2]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][2]+m2[1][9]*m1[0][7]*m0[2][7]+m2[1][9]*m1[0][2]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][7]-m2[1][7]*m1[2][7]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][7]+m2[1][7]*m1[0][7]*m0[2][9]-m2[1][2]*m1[2][9]*m0[0][9]+m2[1][2]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][2]+m2[0][9]*m1[2][7]*m0[1][7]+m2[0][9]*m1[2][2]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][2]-m2[0][9]*m1[1][7]*m0[2][7]-m2[0][9]*m1[1][2]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][7]+m2[0][7]*m1[2][7]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][7]-m2[0][7]*m1[1][7]*m0[2][9]+m2[0][2]*m1[2][9]*m0[1][9]-m2[0][2]*m1[1][9]*m0[2][9]; M1(row,77) = m2[2][9]*m1[1][9]*m0[0][3]+m2[2][9]*m1[1][8]*m0[0][6]+m2[2][9]*m1[1][6]*m0[0][8]+m2[2][9]*m1[1][3]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][3]-m2[2][9]*m1[0][8]*m0[1][6]-m2[2][9]*m1[0][6]*m0[1][8]-m2[2][9]*m1[0][3]*m0[1][9]+m2[2][8]*m1[1][9]*m0[0][6]+m2[2][8]*m1[1][6]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][6]-m2[2][8]*m1[0][6]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][8]+m2[2][6]*m1[1][8]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][8]-m2[2][6]*m1[0][8]*m0[1][9]+m2[2][3]*m1[1][9]*m0[0][9]-m2[2][3]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][3]-m2[1][9]*m1[2][8]*m0[0][6]-m2[1][9]*m1[2][6]*m0[0][8]-m2[1][9]*m1[2][3]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][3]+m2[1][9]*m1[0][8]*m0[2][6]+m2[1][9]*m1[0][6]*m0[2][8]+m2[1][9]*m1[0][3]*m0[2][9]-m2[1][8]*m1[2][9]*m0[0][6]-m2[1][8]*m1[2][6]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][6]+m2[1][8]*m1[0][6]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][8]-m2[1][6]*m1[2][8]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][8]+m2[1][6]*m1[0][8]*m0[2][9]-m2[1][3]*m1[2][9]*m0[0][9]+m2[1][3]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][3]+m2[0][9]*m1[2][8]*m0[1][6]+m2[0][9]*m1[2][6]*m0[1][8]+m2[0][9]*m1[2][3]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][3]-m2[0][9]*m1[1][8]*m0[2][6]-m2[0][9]*m1[1][6]*m0[2][8]-m2[0][9]*m1[1][3]*m0[2][9]+m2[0][8]*m1[2][9]*m0[1][6]+m2[0][8]*m1[2][6]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][6]-m2[0][8]*m1[1][6]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][8]+m2[0][6]*m1[2][8]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][8]-m2[0][6]*m1[1][8]*m0[2][9]+m2[0][3]*m1[2][9]*m0[1][9]-m2[0][3]*m1[1][9]*m0[2][9]; M1(row,78) = m2[2][9]*m1[1][9]*m0[0][4]+m2[2][9]*m1[1][8]*m0[0][7]+m2[2][9]*m1[1][7]*m0[0][8]+m2[2][9]*m1[1][4]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][4]-m2[2][9]*m1[0][8]*m0[1][7]-m2[2][9]*m1[0][7]*m0[1][8]-m2[2][9]*m1[0][4]*m0[1][9]+m2[2][8]*m1[1][9]*m0[0][7]+m2[2][8]*m1[1][7]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][7]-m2[2][8]*m1[0][7]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][8]+m2[2][7]*m1[1][8]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][8]-m2[2][7]*m1[0][8]*m0[1][9]+m2[2][4]*m1[1][9]*m0[0][9]-m2[2][4]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][4]-m2[1][9]*m1[2][8]*m0[0][7]-m2[1][9]*m1[2][7]*m0[0][8]-m2[1][9]*m1[2][4]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][4]+m2[1][9]*m1[0][8]*m0[2][7]+m2[1][9]*m1[0][7]*m0[2][8]+m2[1][9]*m1[0][4]*m0[2][9]-m2[1][8]*m1[2][9]*m0[0][7]-m2[1][8]*m1[2][7]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][7]+m2[1][8]*m1[0][7]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][8]-m2[1][7]*m1[2][8]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][8]+m2[1][7]*m1[0][8]*m0[2][9]-m2[1][4]*m1[2][9]*m0[0][9]+m2[1][4]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][4]+m2[0][9]*m1[2][8]*m0[1][7]+m2[0][9]*m1[2][7]*m0[1][8]+m2[0][9]*m1[2][4]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][4]-m2[0][9]*m1[1][8]*m0[2][7]-m2[0][9]*m1[1][7]*m0[2][8]-m2[0][9]*m1[1][4]*m0[2][9]+m2[0][8]*m1[2][9]*m0[1][7]+m2[0][8]*m1[2][7]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][7]-m2[0][8]*m1[1][7]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][8]+m2[0][7]*m1[2][8]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][8]-m2[0][7]*m1[1][8]*m0[2][9]+m2[0][4]*m1[2][9]*m0[1][9]-m2[0][4]*m1[1][9]*m0[2][9]; M1(row,79) = m2[2][9]*m1[1][9]*m0[0][5]+m2[2][9]*m1[1][8]*m0[0][8]+m2[2][9]*m1[1][5]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][5]-m2[2][9]*m1[0][8]*m0[1][8]-m2[2][9]*m1[0][5]*m0[1][9]+m2[2][8]*m1[1][9]*m0[0][8]+m2[2][8]*m1[1][8]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][8]-m2[2][8]*m1[0][8]*m0[1][9]+m2[2][5]*m1[1][9]*m0[0][9]-m2[2][5]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][5]-m2[1][9]*m1[2][8]*m0[0][8]-m2[1][9]*m1[2][5]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][5]+m2[1][9]*m1[0][8]*m0[2][8]+m2[1][9]*m1[0][5]*m0[2][9]-m2[1][8]*m1[2][9]*m0[0][8]-m2[1][8]*m1[2][8]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][8]+m2[1][8]*m1[0][8]*m0[2][9]-m2[1][5]*m1[2][9]*m0[0][9]+m2[1][5]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][5]+m2[0][9]*m1[2][8]*m0[1][8]+m2[0][9]*m1[2][5]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][5]-m2[0][9]*m1[1][8]*m0[2][8]-m2[0][9]*m1[1][5]*m0[2][9]+m2[0][8]*m1[2][9]*m0[1][8]+m2[0][8]*m1[2][8]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][8]-m2[0][8]*m1[1][8]*m0[2][9]+m2[0][5]*m1[2][9]*m0[1][9]-m2[0][5]*m1[1][9]*m0[2][9]; M1(row,80) = m2[2][9]*m1[1][9]*m0[0][6]+m2[2][9]*m1[1][6]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][6]-m2[2][9]*m1[0][6]*m0[1][9]+m2[2][6]*m1[1][9]*m0[0][9]-m2[2][6]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][6]-m2[1][9]*m1[2][6]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][6]+m2[1][9]*m1[0][6]*m0[2][9]-m2[1][6]*m1[2][9]*m0[0][9]+m2[1][6]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][6]+m2[0][9]*m1[2][6]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][6]-m2[0][9]*m1[1][6]*m0[2][9]+m2[0][6]*m1[2][9]*m0[1][9]-m2[0][6]*m1[1][9]*m0[2][9]; M1(row,81) = m2[2][9]*m1[1][9]*m0[0][7]+m2[2][9]*m1[1][7]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][7]-m2[2][9]*m1[0][7]*m0[1][9]+m2[2][7]*m1[1][9]*m0[0][9]-m2[2][7]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][7]-m2[1][9]*m1[2][7]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][7]+m2[1][9]*m1[0][7]*m0[2][9]-m2[1][7]*m1[2][9]*m0[0][9]+m2[1][7]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][7]+m2[0][9]*m1[2][7]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][7]-m2[0][9]*m1[1][7]*m0[2][9]+m2[0][7]*m1[2][9]*m0[1][9]-m2[0][7]*m1[1][9]*m0[2][9]; M1(row,82) = m2[2][9]*m1[1][9]*m0[0][8]+m2[2][9]*m1[1][8]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][8]-m2[2][9]*m1[0][8]*m0[1][9]+m2[2][8]*m1[1][9]*m0[0][9]-m2[2][8]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][8]-m2[1][9]*m1[2][8]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][8]+m2[1][9]*m1[0][8]*m0[2][9]-m2[1][8]*m1[2][9]*m0[0][9]+m2[1][8]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][8]+m2[0][9]*m1[2][8]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][8]-m2[0][9]*m1[1][8]*m0[2][9]+m2[0][8]*m1[2][9]*m0[1][9]-m2[0][8]*m1[1][9]*m0[2][9]; M1(row,83) = m2[2][9]*m1[1][9]*m0[0][9]-m2[2][9]*m1[0][9]*m0[1][9]-m2[1][9]*m1[2][9]*m0[0][9]+m2[1][9]*m1[0][9]*m0[2][9]+m2[0][9]*m1[2][9]*m0[1][9]-m2[0][9]*m1[1][9]*m0[2][9]; } #if EQS > 50 #define DECA_EQS 6 #else #if EQS > 40 #define DECA_EQS 5 #else #if EQS > 30 #define DECA_EQS 4 #else #if EQS > 20 #define DECA_EQS 3 #else #define DECA_EQS 2 #endif #endif #endif #endif void opengv::relative_pose::modules::sixpt::setupAction( const std::vector,Eigen::aligned_allocator< Eigen::Matrix > > & L1, const std::vector,Eigen::aligned_allocator< Eigen::Matrix > > & L2, Eigen::Matrix & Action ) { std::vector m[DECA_EQS][5][3]; for( int primI = 0; primI < DECA_EQS; primI++ ) { for( int secI = 0; secI < 6; secI++ ) { if( primI != secI ) { const Eigen::Matrix & l01 = L1[primI]; const Eigen::Matrix & l02 = L2[primI]; const Eigen::Matrix & l11 = L1[secI]; const Eigen::Matrix & l12 = L2[secI]; int r = secI; if(secI > primI) r--; fillRow1( l01, l02, l11, l12, m[primI][r][0], m[primI][r][1], m[primI][r][2] ); } } } Eigen::Matrix M1p = Eigen::Matrix::Zero(); int decaIndex = 0; int row0 = 0; int row1 = 1; int row2 = 2; for( int row = 0; row < EQS; row++ ) { fillRow2( M1p, row, m[decaIndex][row0], m[decaIndex][row1], m[decaIndex][row2] ); row2++; if( row2 > 4 ) { row1++; row2 = row1 + 1; if( row1 > 3 ) { row0++; row1 = row0 + 1; row2 = row1 + 1; if( row0 > 2) { decaIndex++; row0 = 0; row1 = 1; row2 = 2; } } } } //this is currently hardcoded for 15 equations! //Eigen::Matrix M1_part1 = M1.block<15,15>(0,0); //Eigen::Matrix M1_part2 = M1_part1.inverse() * M1; //M1 = M1_part2; Eigen::Matrix B = M1p.block(0,0); Eigen::Matrix Bt = B.transpose(); Eigen::Matrix BtB = Bt * B; Eigen::Matrix M1 = BtB.inverse() * Bt * M1p; Eigen::Matrix M2 = Eigen::Matrix::Zero(); M2(0,23) = M1(14,14); M2(0,24) = M1(14,15); M2(0,25) = M1(14,16); M2(0,26) = M1(14,17); M2(0,27) = M1(14,18); M2(0,28) = M1(14,19); M2(0,29) = M1(14,20); M2(0,30) = M1(14,21); M2(0,31) = M1(14,22); M2(0,32) = M1(14,23); M2(0,33) = M1(14,24); M2(0,34) = M1(14,25); M2(0,35) = M1(14,26); M2(0,36) = M1(14,27); M2(0,52) = M1(14,28); M2(0,53) = M1(14,29); M2(0,54) = M1(14,30); M2(0,55) = M1(14,31); M2(0,56) = M1(14,32); M2(0,57) = M1(14,33); M2(0,58) = M1(14,34); M2(0,59) = M1(14,35); M2(0,60) = M1(14,36); M2(0,61) = M1(14,37); M2(0,62) = M1(14,38); M2(0,63) = M1(14,39); M2(0,64) = M1(14,40); M2(0,65) = M1(14,41); M2(0,66) = M1(14,42); M2(0,67) = M1(14,43); M2(0,68) = M1(14,44); M2(0,69) = M1(14,45); M2(0,70) = M1(14,46); M2(0,71) = M1(14,47); M2(0,85) = M1(14,49); M2(0,86) = M1(14,50); M2(0,87) = M1(14,51); M2(0,88) = M1(14,52); M2(0,89) = M1(14,53); M2(0,90) = M1(14,54); M2(0,91) = M1(14,55); M2(0,92) = M1(14,56); M2(0,93) = M1(14,48); M2(0,94) = M1(14,57); M2(0,95) = M1(14,58); M2(0,96) = M1(14,59); M2(0,97) = M1(14,60); M2(0,98) = M1(14,61); M2(0,99) = M1(14,62); M2(0,100) = M1(14,63); M2(0,112) = M1(14,64); M2(0,113) = M1(14,65); M2(0,114) = M1(14,66); M2(0,115) = M1(14,67); M2(0,116) = M1(14,68); M2(0,117) = M1(14,69); M2(0,118) = M1(14,70); M2(0,119) = M1(14,71); M2(0,120) = M1(14,72); M2(0,121) = M1(14,73); M2(0,131) = M1(14,74); M2(0,132) = M1(14,75); M2(0,133) = M1(14,76); M2(0,134) = M1(14,77); M2(0,135) = M1(14,78); M2(0,136) = M1(14,79); M2(0,144) = M1(14,80); M2(0,145) = M1(14,81); M2(0,146) = M1(14,82); M2(0,152) = M1(14,83); M2(1,18) = M1(14,14); M2(1,19) = M1(14,15); M2(1,20) = M1(14,16); M2(1,21) = M1(14,17); M2(1,23) = M1(14,18); M2(1,24) = M1(14,19); M2(1,25) = M1(14,20); M2(1,26) = M1(14,21); M2(1,28) = M1(14,22); M2(1,29) = M1(14,23); M2(1,30) = M1(14,24); M2(1,32) = M1(14,25); M2(1,33) = M1(14,26); M2(1,35) = M1(14,27); M2(1,46) = M1(14,28); M2(1,47) = M1(14,29); M2(1,48) = M1(14,30); M2(1,49) = M1(14,31); M2(1,50) = M1(14,32); M2(1,51) = M1(14,33); M2(1,53) = M1(14,34); M2(1,54) = M1(14,35); M2(1,55) = M1(14,36); M2(1,56) = M1(14,37); M2(1,57) = M1(14,38); M2(1,59) = M1(14,39); M2(1,60) = M1(14,40); M2(1,61) = M1(14,41); M2(1,62) = M1(14,42); M2(1,64) = M1(14,43); M2(1,65) = M1(14,44); M2(1,66) = M1(14,45); M2(1,68) = M1(14,46); M2(1,69) = M1(14,47); M2(1,71) = M1(14,48); M2(1,80) = M1(14,49); M2(1,81) = M1(14,50); M2(1,82) = M1(14,51); M2(1,83) = M1(14,52); M2(1,84) = M1(14,53); M2(1,86) = M1(14,54); M2(1,87) = M1(14,55); M2(1,88) = M1(14,56); M2(1,89) = M1(14,57); M2(1,91) = M1(14,58); M2(1,92) = M1(14,59); M2(1,94) = M1(14,60); M2(1,96) = M1(14,61); M2(1,97) = M1(14,62); M2(1,99) = M1(14,63); M2(1,108) = M1(14,64); M2(1,109) = M1(14,65); M2(1,110) = M1(14,66); M2(1,111) = M1(14,67); M2(1,113) = M1(14,68); M2(1,114) = M1(14,69); M2(1,115) = M1(14,70); M2(1,117) = M1(14,71); M2(1,118) = M1(14,72); M2(1,120) = M1(14,73); M2(1,128) = M1(14,74); M2(1,129) = M1(14,75); M2(1,130) = M1(14,76); M2(1,132) = M1(14,77); M2(1,133) = M1(14,78); M2(1,135) = M1(14,79); M2(1,142) = M1(14,80); M2(1,143) = M1(14,81); M2(1,145) = M1(14,82); M2(1,151) = M1(14,83); M2(2,6) = M1(8,8); M2(2,13) = M1(8,15); M2(2,14) = M1(8,16); M2(2,15) = M1(8,17); M2(2,18) = M1(8,18); M2(2,19) = M1(8,19); M2(2,20) = M1(8,20); M2(2,21) = M1(8,21); M2(2,24) = M1(8,22); M2(2,25) = M1(8,23); M2(2,26) = M1(8,24); M2(2,29) = M1(8,25); M2(2,30) = M1(8,26); M2(2,33) = M1(8,27); M2(2,39) = M1(8,28); M2(2,40) = M1(8,29); M2(2,41) = M1(8,30); M2(2,42) = M1(8,31); M2(2,43) = M1(8,32); M2(2,44) = M1(8,33); M2(2,47) = M1(8,34); M2(2,48) = M1(8,35); M2(2,49) = M1(8,36); M2(2,50) = M1(8,37); M2(2,51) = M1(8,38); M2(2,54) = M1(8,39); M2(2,55) = M1(8,40); M2(2,56) = M1(8,41); M2(2,57) = M1(8,42); M2(2,60) = M1(8,43); M2(2,61) = M1(8,44); M2(2,62) = M1(8,45); M2(2,65) = M1(8,46); M2(2,66) = M1(8,47); M2(2,69) = M1(8,48); M2(2,74) = M1(8,49); M2(2,75) = M1(8,50); M2(2,76) = M1(8,51); M2(2,77) = M1(8,52); M2(2,78) = M1(8,53); M2(2,81) = M1(8,54); M2(2,82) = M1(8,55); M2(2,83) = M1(8,56); M2(2,84) = M1(8,57); M2(2,87) = M1(8,58); M2(2,88) = M1(8,59); M2(2,89) = M1(8,60); M2(2,92) = M1(8,61); M2(2,94) = M1(8,62); M2(2,97) = M1(8,63); M2(2,103) = M1(8,64); M2(2,104) = M1(8,65); M2(2,105) = M1(8,66); M2(2,106) = M1(8,67); M2(2,109) = M1(8,68); M2(2,110) = M1(8,69); M2(2,111) = M1(8,70); M2(2,114) = M1(8,71); M2(2,115) = M1(8,72); M2(2,118) = M1(8,73); M2(2,124) = M1(8,74); M2(2,125) = M1(8,75); M2(2,126) = M1(8,76); M2(2,129) = M1(8,77); M2(2,130) = M1(8,78); M2(2,133) = M1(8,79); M2(2,139) = M1(8,80); M2(2,140) = M1(8,81); M2(2,143) = M1(8,82); M2(2,149) = M1(8,83); M2(3,7) = M1(9,9); M2(3,13) = M1(9,15); M2(3,14) = M1(9,16); M2(3,15) = M1(9,17); M2(3,18) = M1(9,18); M2(3,19) = M1(9,19); M2(3,20) = M1(9,20); M2(3,21) = M1(9,21); M2(3,24) = M1(9,22); M2(3,25) = M1(9,23); M2(3,26) = M1(9,24); M2(3,29) = M1(9,25); M2(3,30) = M1(9,26); M2(3,33) = M1(9,27); M2(3,39) = M1(9,28); M2(3,40) = M1(9,29); M2(3,41) = M1(9,30); M2(3,42) = M1(9,31); M2(3,43) = M1(9,32); M2(3,44) = M1(9,33); M2(3,47) = M1(9,34); M2(3,48) = M1(9,35); M2(3,49) = M1(9,36); M2(3,50) = M1(9,37); M2(3,51) = M1(9,38); M2(3,54) = M1(9,39); M2(3,55) = M1(9,40); M2(3,56) = M1(9,41); M2(3,57) = M1(9,42); M2(3,60) = M1(9,43); M2(3,61) = M1(9,44); M2(3,62) = M1(9,45); M2(3,65) = M1(9,46); M2(3,66) = M1(9,47); M2(3,69) = M1(9,48); M2(3,74) = M1(9,49); M2(3,75) = M1(9,50); M2(3,76) = M1(9,51); M2(3,77) = M1(9,52); M2(3,78) = M1(9,53); M2(3,81) = M1(9,54); M2(3,82) = M1(9,55); M2(3,83) = M1(9,56); M2(3,84) = M1(9,57); M2(3,87) = M1(9,58); M2(3,88) = M1(9,59); M2(3,89) = M1(9,60); M2(3,92) = M1(9,61); M2(3,94) = M1(9,62); M2(3,97) = M1(9,63); M2(3,103) = M1(9,64); M2(3,104) = M1(9,65); M2(3,105) = M1(9,66); M2(3,106) = M1(9,67); M2(3,109) = M1(9,68); M2(3,110) = M1(9,69); M2(3,111) = M1(9,70); M2(3,114) = M1(9,71); M2(3,115) = M1(9,72); M2(3,118) = M1(9,73); M2(3,124) = M1(9,74); M2(3,125) = M1(9,75); M2(3,126) = M1(9,76); M2(3,129) = M1(9,77); M2(3,130) = M1(9,78); M2(3,133) = M1(9,79); M2(3,139) = M1(9,80); M2(3,140) = M1(9,81); M2(3,143) = M1(9,82); M2(3,149) = M1(9,83); M2(4,8) = M1(10,10); M2(4,13) = M1(10,15); M2(4,14) = M1(10,16); M2(4,15) = M1(10,17); M2(4,18) = M1(10,18); M2(4,19) = M1(10,19); M2(4,20) = M1(10,20); M2(4,21) = M1(10,21); M2(4,24) = M1(10,22); M2(4,25) = M1(10,23); M2(4,26) = M1(10,24); M2(4,29) = M1(10,25); M2(4,30) = M1(10,26); M2(4,33) = M1(10,27); M2(4,39) = M1(10,28); M2(4,40) = M1(10,29); M2(4,41) = M1(10,30); M2(4,42) = M1(10,31); M2(4,43) = M1(10,32); M2(4,44) = M1(10,33); M2(4,47) = M1(10,34); M2(4,48) = M1(10,35); M2(4,49) = M1(10,36); M2(4,50) = M1(10,37); M2(4,51) = M1(10,38); M2(4,54) = M1(10,39); M2(4,55) = M1(10,40); M2(4,56) = M1(10,41); M2(4,57) = M1(10,42); M2(4,60) = M1(10,43); M2(4,61) = M1(10,44); M2(4,62) = M1(10,45); M2(4,65) = M1(10,46); M2(4,66) = M1(10,47); M2(4,69) = M1(10,48); M2(4,74) = M1(10,49); M2(4,75) = M1(10,50); M2(4,76) = M1(10,51); M2(4,77) = M1(10,52); M2(4,78) = M1(10,53); M2(4,81) = M1(10,54); M2(4,82) = M1(10,55); M2(4,83) = M1(10,56); M2(4,84) = M1(10,57); M2(4,87) = M1(10,58); M2(4,88) = M1(10,59); M2(4,89) = M1(10,60); M2(4,92) = M1(10,61); M2(4,94) = M1(10,62); M2(4,97) = M1(10,63); M2(4,103) = M1(10,64); M2(4,104) = M1(10,65); M2(4,105) = M1(10,66); M2(4,106) = M1(10,67); M2(4,109) = M1(10,68); M2(4,110) = M1(10,69); M2(4,111) = M1(10,70); M2(4,114) = M1(10,71); M2(4,115) = M1(10,72); M2(4,118) = M1(10,73); M2(4,124) = M1(10,74); M2(4,125) = M1(10,75); M2(4,126) = M1(10,76); M2(4,129) = M1(10,77); M2(4,130) = M1(10,78); M2(4,133) = M1(10,79); M2(4,139) = M1(10,80); M2(4,140) = M1(10,81); M2(4,143) = M1(10,82); M2(4,149) = M1(10,83); M2(5,9) = M1(11,11); M2(5,13) = M1(11,15); M2(5,14) = M1(11,16); M2(5,15) = M1(11,17); M2(5,18) = M1(11,18); M2(5,19) = M1(11,19); M2(5,20) = M1(11,20); M2(5,21) = M1(11,21); M2(5,24) = M1(11,22); M2(5,25) = M1(11,23); M2(5,26) = M1(11,24); M2(5,29) = M1(11,25); M2(5,30) = M1(11,26); M2(5,33) = M1(11,27); M2(5,39) = M1(11,28); M2(5,40) = M1(11,29); M2(5,41) = M1(11,30); M2(5,42) = M1(11,31); M2(5,43) = M1(11,32); M2(5,44) = M1(11,33); M2(5,47) = M1(11,34); M2(5,48) = M1(11,35); M2(5,49) = M1(11,36); M2(5,50) = M1(11,37); M2(5,51) = M1(11,38); M2(5,54) = M1(11,39); M2(5,55) = M1(11,40); M2(5,56) = M1(11,41); M2(5,57) = M1(11,42); M2(5,60) = M1(11,43); M2(5,61) = M1(11,44); M2(5,62) = M1(11,45); M2(5,65) = M1(11,46); M2(5,66) = M1(11,47); M2(5,69) = M1(11,48); M2(5,74) = M1(11,49); M2(5,75) = M1(11,50); M2(5,76) = M1(11,51); M2(5,77) = M1(11,52); M2(5,78) = M1(11,53); M2(5,81) = M1(11,54); M2(5,82) = M1(11,55); M2(5,83) = M1(11,56); M2(5,84) = M1(11,57); M2(5,87) = M1(11,58); M2(5,88) = M1(11,59); M2(5,89) = M1(11,60); M2(5,92) = M1(11,61); M2(5,94) = M1(11,62); M2(5,97) = M1(11,63); M2(5,103) = M1(11,64); M2(5,104) = M1(11,65); M2(5,105) = M1(11,66); M2(5,106) = M1(11,67); M2(5,109) = M1(11,68); M2(5,110) = M1(11,69); M2(5,111) = M1(11,70); M2(5,114) = M1(11,71); M2(5,115) = M1(11,72); M2(5,118) = M1(11,73); M2(5,124) = M1(11,74); M2(5,125) = M1(11,75); M2(5,126) = M1(11,76); M2(5,129) = M1(11,77); M2(5,130) = M1(11,78); M2(5,133) = M1(11,79); M2(5,139) = M1(11,80); M2(5,140) = M1(11,81); M2(5,143) = M1(11,82); M2(5,149) = M1(11,83); M2(6,11) = M1(13,13); M2(6,13) = M1(13,15); M2(6,14) = M1(13,16); M2(6,15) = M1(13,17); M2(6,18) = M1(13,18); M2(6,19) = M1(13,19); M2(6,20) = M1(13,20); M2(6,21) = M1(13,21); M2(6,24) = M1(13,22); M2(6,25) = M1(13,23); M2(6,26) = M1(13,24); M2(6,29) = M1(13,25); M2(6,30) = M1(13,26); M2(6,33) = M1(13,27); M2(6,39) = M1(13,28); M2(6,40) = M1(13,29); M2(6,41) = M1(13,30); M2(6,42) = M1(13,31); M2(6,43) = M1(13,32); M2(6,44) = M1(13,33); M2(6,47) = M1(13,34); M2(6,48) = M1(13,35); M2(6,49) = M1(13,36); M2(6,50) = M1(13,37); M2(6,51) = M1(13,38); M2(6,54) = M1(13,39); M2(6,55) = M1(13,40); M2(6,56) = M1(13,41); M2(6,57) = M1(13,42); M2(6,60) = M1(13,43); M2(6,61) = M1(13,44); M2(6,62) = M1(13,45); M2(6,65) = M1(13,46); M2(6,66) = M1(13,47); M2(6,69) = M1(13,48); M2(6,74) = M1(13,49); M2(6,75) = M1(13,50); M2(6,76) = M1(13,51); M2(6,77) = M1(13,52); M2(6,78) = M1(13,53); M2(6,81) = M1(13,54); M2(6,82) = M1(13,55); M2(6,83) = M1(13,56); M2(6,84) = M1(13,57); M2(6,87) = M1(13,58); M2(6,88) = M1(13,59); M2(6,89) = M1(13,60); M2(6,92) = M1(13,61); M2(6,94) = M1(13,62); M2(6,97) = M1(13,63); M2(6,103) = M1(13,64); M2(6,104) = M1(13,65); M2(6,105) = M1(13,66); M2(6,106) = M1(13,67); M2(6,109) = M1(13,68); M2(6,110) = M1(13,69); M2(6,111) = M1(13,70); M2(6,114) = M1(13,71); M2(6,115) = M1(13,72); M2(6,118) = M1(13,73); M2(6,124) = M1(13,74); M2(6,125) = M1(13,75); M2(6,126) = M1(13,76); M2(6,129) = M1(13,77); M2(6,130) = M1(13,78); M2(6,133) = M1(13,79); M2(6,139) = M1(13,80); M2(6,140) = M1(13,81); M2(6,143) = M1(13,82); M2(6,149) = M1(13,83); M2(7,12) = M1(14,14); M2(7,13) = M1(14,15); M2(7,14) = M1(14,16); M2(7,15) = M1(14,17); M2(7,18) = M1(14,18); M2(7,19) = M1(14,19); M2(7,20) = M1(14,20); M2(7,21) = M1(14,21); M2(7,24) = M1(14,22); M2(7,25) = M1(14,23); M2(7,26) = M1(14,24); M2(7,29) = M1(14,25); M2(7,30) = M1(14,26); M2(7,33) = M1(14,27); M2(7,39) = M1(14,28); M2(7,40) = M1(14,29); M2(7,41) = M1(14,30); M2(7,42) = M1(14,31); M2(7,43) = M1(14,32); M2(7,44) = M1(14,33); M2(7,47) = M1(14,34); M2(7,48) = M1(14,35); M2(7,49) = M1(14,36); M2(7,50) = M1(14,37); M2(7,51) = M1(14,38); M2(7,54) = M1(14,39); M2(7,55) = M1(14,40); M2(7,56) = M1(14,41); M2(7,57) = M1(14,42); M2(7,60) = M1(14,43); M2(7,61) = M1(14,44); M2(7,62) = M1(14,45); M2(7,65) = M1(14,46); M2(7,66) = M1(14,47); M2(7,69) = M1(14,48); M2(7,74) = M1(14,49); M2(7,75) = M1(14,50); M2(7,76) = M1(14,51); M2(7,77) = M1(14,52); M2(7,78) = M1(14,53); M2(7,81) = M1(14,54); M2(7,82) = M1(14,55); M2(7,83) = M1(14,56); M2(7,84) = M1(14,57); M2(7,87) = M1(14,58); M2(7,88) = M1(14,59); M2(7,89) = M1(14,60); M2(7,92) = M1(14,61); M2(7,94) = M1(14,62); M2(7,97) = M1(14,63); M2(7,103) = M1(14,64); M2(7,104) = M1(14,65); M2(7,105) = M1(14,66); M2(7,106) = M1(14,67); M2(7,109) = M1(14,68); M2(7,110) = M1(14,69); M2(7,111) = M1(14,70); M2(7,114) = M1(14,71); M2(7,115) = M1(14,72); M2(7,118) = M1(14,73); M2(7,124) = M1(14,74); M2(7,125) = M1(14,75); M2(7,126) = M1(14,76); M2(7,129) = M1(14,77); M2(7,130) = M1(14,78); M2(7,133) = M1(14,79); M2(7,139) = M1(14,80); M2(7,140) = M1(14,81); M2(7,143) = M1(14,82); M2(7,149) = M1(14,83); M2(8,10) = M1(8,8); M2(8,18) = M1(8,15); M2(8,19) = M1(8,16); M2(8,20) = M1(8,17); M2(8,22) = M1(8,18); M2(8,23) = M1(8,19); M2(8,24) = M1(8,20); M2(8,25) = M1(8,21); M2(8,27) = M1(8,22); M2(8,28) = M1(8,23); M2(8,29) = M1(8,24); M2(8,31) = M1(8,25); M2(8,32) = M1(8,26); M2(8,34) = M1(8,27); M2(8,45) = M1(8,28); M2(8,46) = M1(8,29); M2(8,47) = M1(8,30); M2(8,48) = M1(8,31); M2(8,49) = M1(8,32); M2(8,50) = M1(8,33); M2(8,52) = M1(8,34); M2(8,53) = M1(8,35); M2(8,54) = M1(8,36); M2(8,55) = M1(8,37); M2(8,56) = M1(8,38); M2(8,58) = M1(8,39); M2(8,59) = M1(8,40); M2(8,60) = M1(8,41); M2(8,61) = M1(8,42); M2(8,63) = M1(8,43); M2(8,64) = M1(8,44); M2(8,65) = M1(8,45); M2(8,67) = M1(8,46); M2(8,68) = M1(8,47); M2(8,70) = M1(8,48); M2(8,79) = M1(8,49); M2(8,80) = M1(8,50); M2(8,81) = M1(8,51); M2(8,82) = M1(8,52); M2(8,83) = M1(8,53); M2(8,85) = M1(8,54); M2(8,86) = M1(8,55); M2(8,87) = M1(8,56); M2(8,88) = M1(8,57); M2(8,90) = M1(8,58); M2(8,91) = M1(8,59); M2(8,92) = M1(8,60); M2(8,95) = M1(8,61); M2(8,96) = M1(8,62); M2(8,98) = M1(8,63); M2(8,107) = M1(8,64); M2(8,108) = M1(8,65); M2(8,109) = M1(8,66); M2(8,110) = M1(8,67); M2(8,112) = M1(8,68); M2(8,113) = M1(8,69); M2(8,114) = M1(8,70); M2(8,116) = M1(8,71); M2(8,117) = M1(8,72); M2(8,119) = M1(8,73); M2(8,127) = M1(8,74); M2(8,128) = M1(8,75); M2(8,129) = M1(8,76); M2(8,131) = M1(8,77); M2(8,132) = M1(8,78); M2(8,134) = M1(8,79); M2(8,141) = M1(8,80); M2(8,142) = M1(8,81); M2(8,144) = M1(8,82); M2(8,150) = M1(8,83); M2(9,11) = M1(9,9); M2(9,18) = M1(9,15); M2(9,19) = M1(9,16); M2(9,20) = M1(9,17); M2(9,22) = M1(9,18); M2(9,23) = M1(9,19); M2(9,24) = M1(9,20); M2(9,25) = M1(9,21); M2(9,27) = M1(9,22); M2(9,28) = M1(9,23); M2(9,29) = M1(9,24); M2(9,31) = M1(9,25); M2(9,32) = M1(9,26); M2(9,34) = M1(9,27); M2(9,45) = M1(9,28); M2(9,46) = M1(9,29); M2(9,47) = M1(9,30); M2(9,48) = M1(9,31); M2(9,49) = M1(9,32); M2(9,50) = M1(9,33); M2(9,52) = M1(9,34); M2(9,53) = M1(9,35); M2(9,54) = M1(9,36); M2(9,55) = M1(9,37); M2(9,56) = M1(9,38); M2(9,58) = M1(9,39); M2(9,59) = M1(9,40); M2(9,60) = M1(9,41); M2(9,61) = M1(9,42); M2(9,63) = M1(9,43); M2(9,64) = M1(9,44); M2(9,65) = M1(9,45); M2(9,67) = M1(9,46); M2(9,68) = M1(9,47); M2(9,70) = M1(9,48); M2(9,79) = M1(9,49); M2(9,80) = M1(9,50); M2(9,81) = M1(9,51); M2(9,82) = M1(9,52); M2(9,83) = M1(9,53); M2(9,85) = M1(9,54); M2(9,86) = M1(9,55); M2(9,87) = M1(9,56); M2(9,88) = M1(9,57); M2(9,90) = M1(9,58); M2(9,91) = M1(9,59); M2(9,92) = M1(9,60); M2(9,95) = M1(9,61); M2(9,96) = M1(9,62); M2(9,98) = M1(9,63); M2(9,107) = M1(9,64); M2(9,108) = M1(9,65); M2(9,109) = M1(9,66); M2(9,110) = M1(9,67); M2(9,112) = M1(9,68); M2(9,113) = M1(9,69); M2(9,114) = M1(9,70); M2(9,116) = M1(9,71); M2(9,117) = M1(9,72); M2(9,119) = M1(9,73); M2(9,127) = M1(9,74); M2(9,128) = M1(9,75); M2(9,129) = M1(9,76); M2(9,131) = M1(9,77); M2(9,132) = M1(9,78); M2(9,134) = M1(9,79); M2(9,141) = M1(9,80); M2(9,142) = M1(9,81); M2(9,144) = M1(9,82); M2(9,150) = M1(9,83); M2(10,12) = M1(10,10); M2(10,18) = M1(10,15); M2(10,19) = M1(10,16); M2(10,20) = M1(10,17); M2(10,22) = M1(10,18); M2(10,23) = M1(10,19); M2(10,24) = M1(10,20); M2(10,25) = M1(10,21); M2(10,27) = M1(10,22); M2(10,28) = M1(10,23); M2(10,29) = M1(10,24); M2(10,31) = M1(10,25); M2(10,32) = M1(10,26); M2(10,34) = M1(10,27); M2(10,45) = M1(10,28); M2(10,46) = M1(10,29); M2(10,47) = M1(10,30); M2(10,48) = M1(10,31); M2(10,49) = M1(10,32); M2(10,50) = M1(10,33); M2(10,52) = M1(10,34); M2(10,53) = M1(10,35); M2(10,54) = M1(10,36); M2(10,55) = M1(10,37); M2(10,56) = M1(10,38); M2(10,58) = M1(10,39); M2(10,59) = M1(10,40); M2(10,60) = M1(10,41); M2(10,61) = M1(10,42); M2(10,63) = M1(10,43); M2(10,64) = M1(10,44); M2(10,65) = M1(10,45); M2(10,67) = M1(10,46); M2(10,68) = M1(10,47); M2(10,70) = M1(10,48); M2(10,79) = M1(10,49); M2(10,80) = M1(10,50); M2(10,81) = M1(10,51); M2(10,82) = M1(10,52); M2(10,83) = M1(10,53); M2(10,85) = M1(10,54); M2(10,86) = M1(10,55); M2(10,87) = M1(10,56); M2(10,88) = M1(10,57); M2(10,90) = M1(10,58); M2(10,91) = M1(10,59); M2(10,92) = M1(10,60); M2(10,95) = M1(10,61); M2(10,96) = M1(10,62); M2(10,98) = M1(10,63); M2(10,107) = M1(10,64); M2(10,108) = M1(10,65); M2(10,109) = M1(10,66); M2(10,110) = M1(10,67); M2(10,112) = M1(10,68); M2(10,113) = M1(10,69); M2(10,114) = M1(10,70); M2(10,116) = M1(10,71); M2(10,117) = M1(10,72); M2(10,119) = M1(10,73); M2(10,127) = M1(10,74); M2(10,128) = M1(10,75); M2(10,129) = M1(10,76); M2(10,131) = M1(10,77); M2(10,132) = M1(10,78); M2(10,134) = M1(10,79); M2(10,141) = M1(10,80); M2(10,142) = M1(10,81); M2(10,144) = M1(10,82); M2(10,150) = M1(10,83); M2(11,13) = M1(11,11); M2(11,18) = M1(11,15); M2(11,19) = M1(11,16); M2(11,20) = M1(11,17); M2(11,22) = M1(11,18); M2(11,23) = M1(11,19); M2(11,24) = M1(11,20); M2(11,25) = M1(11,21); M2(11,27) = M1(11,22); M2(11,28) = M1(11,23); M2(11,29) = M1(11,24); M2(11,31) = M1(11,25); M2(11,32) = M1(11,26); M2(11,34) = M1(11,27); M2(11,45) = M1(11,28); M2(11,46) = M1(11,29); M2(11,47) = M1(11,30); M2(11,48) = M1(11,31); M2(11,49) = M1(11,32); M2(11,50) = M1(11,33); M2(11,52) = M1(11,34); M2(11,53) = M1(11,35); M2(11,54) = M1(11,36); M2(11,55) = M1(11,37); M2(11,56) = M1(11,38); M2(11,58) = M1(11,39); M2(11,59) = M1(11,40); M2(11,60) = M1(11,41); M2(11,61) = M1(11,42); M2(11,63) = M1(11,43); M2(11,64) = M1(11,44); M2(11,65) = M1(11,45); M2(11,67) = M1(11,46); M2(11,68) = M1(11,47); M2(11,70) = M1(11,48); M2(11,79) = M1(11,49); M2(11,80) = M1(11,50); M2(11,81) = M1(11,51); M2(11,82) = M1(11,52); M2(11,83) = M1(11,53); M2(11,85) = M1(11,54); M2(11,86) = M1(11,55); M2(11,87) = M1(11,56); M2(11,88) = M1(11,57); M2(11,90) = M1(11,58); M2(11,91) = M1(11,59); M2(11,92) = M1(11,60); M2(11,95) = M1(11,61); M2(11,96) = M1(11,62); M2(11,98) = M1(11,63); M2(11,107) = M1(11,64); M2(11,108) = M1(11,65); M2(11,109) = M1(11,66); M2(11,110) = M1(11,67); M2(11,112) = M1(11,68); M2(11,113) = M1(11,69); M2(11,114) = M1(11,70); M2(11,116) = M1(11,71); M2(11,117) = M1(11,72); M2(11,119) = M1(11,73); M2(11,127) = M1(11,74); M2(11,128) = M1(11,75); M2(11,129) = M1(11,76); M2(11,131) = M1(11,77); M2(11,132) = M1(11,78); M2(11,134) = M1(11,79); M2(11,141) = M1(11,80); M2(11,142) = M1(11,81); M2(11,144) = M1(11,82); M2(11,150) = M1(11,83); M2(12,14) = M1(12,12); M2(12,18) = M1(12,15); M2(12,19) = M1(12,16); M2(12,20) = M1(12,17); M2(12,22) = M1(12,18); M2(12,23) = M1(12,19); M2(12,24) = M1(12,20); M2(12,25) = M1(12,21); M2(12,27) = M1(12,22); M2(12,28) = M1(12,23); M2(12,29) = M1(12,24); M2(12,31) = M1(12,25); M2(12,32) = M1(12,26); M2(12,34) = M1(12,27); M2(12,45) = M1(12,28); M2(12,46) = M1(12,29); M2(12,47) = M1(12,30); M2(12,48) = M1(12,31); M2(12,49) = M1(12,32); M2(12,50) = M1(12,33); M2(12,52) = M1(12,34); M2(12,53) = M1(12,35); M2(12,54) = M1(12,36); M2(12,55) = M1(12,37); M2(12,56) = M1(12,38); M2(12,58) = M1(12,39); M2(12,59) = M1(12,40); M2(12,60) = M1(12,41); M2(12,61) = M1(12,42); M2(12,63) = M1(12,43); M2(12,64) = M1(12,44); M2(12,65) = M1(12,45); M2(12,67) = M1(12,46); M2(12,68) = M1(12,47); M2(12,70) = M1(12,48); M2(12,79) = M1(12,49); M2(12,80) = M1(12,50); M2(12,81) = M1(12,51); M2(12,82) = M1(12,52); M2(12,83) = M1(12,53); M2(12,85) = M1(12,54); M2(12,86) = M1(12,55); M2(12,87) = M1(12,56); M2(12,88) = M1(12,57); M2(12,90) = M1(12,58); M2(12,91) = M1(12,59); M2(12,92) = M1(12,60); M2(12,95) = M1(12,61); M2(12,96) = M1(12,62); M2(12,98) = M1(12,63); M2(12,107) = M1(12,64); M2(12,108) = M1(12,65); M2(12,109) = M1(12,66); M2(12,110) = M1(12,67); M2(12,112) = M1(12,68); M2(12,113) = M1(12,69); M2(12,114) = M1(12,70); M2(12,116) = M1(12,71); M2(12,117) = M1(12,72); M2(12,119) = M1(12,73); M2(12,127) = M1(12,74); M2(12,128) = M1(12,75); M2(12,129) = M1(12,76); M2(12,131) = M1(12,77); M2(12,132) = M1(12,78); M2(12,134) = M1(12,79); M2(12,141) = M1(12,80); M2(12,142) = M1(12,81); M2(12,144) = M1(12,82); M2(12,150) = M1(12,83); M2(13,16) = M1(13,13); M2(13,18) = M1(13,15); M2(13,19) = M1(13,16); M2(13,20) = M1(13,17); M2(13,22) = M1(13,18); M2(13,23) = M1(13,19); M2(13,24) = M1(13,20); M2(13,25) = M1(13,21); M2(13,27) = M1(13,22); M2(13,28) = M1(13,23); M2(13,29) = M1(13,24); M2(13,31) = M1(13,25); M2(13,32) = M1(13,26); M2(13,34) = M1(13,27); M2(13,45) = M1(13,28); M2(13,46) = M1(13,29); M2(13,47) = M1(13,30); M2(13,48) = M1(13,31); M2(13,49) = M1(13,32); M2(13,50) = M1(13,33); M2(13,52) = M1(13,34); M2(13,53) = M1(13,35); M2(13,54) = M1(13,36); M2(13,55) = M1(13,37); M2(13,56) = M1(13,38); M2(13,58) = M1(13,39); M2(13,59) = M1(13,40); M2(13,60) = M1(13,41); M2(13,61) = M1(13,42); M2(13,63) = M1(13,43); M2(13,64) = M1(13,44); M2(13,65) = M1(13,45); M2(13,67) = M1(13,46); M2(13,68) = M1(13,47); M2(13,70) = M1(13,48); M2(13,79) = M1(13,49); M2(13,80) = M1(13,50); M2(13,81) = M1(13,51); M2(13,82) = M1(13,52); M2(13,83) = M1(13,53); M2(13,85) = M1(13,54); M2(13,86) = M1(13,55); M2(13,87) = M1(13,56); M2(13,88) = M1(13,57); M2(13,90) = M1(13,58); M2(13,91) = M1(13,59); M2(13,92) = M1(13,60); M2(13,95) = M1(13,61); M2(13,96) = M1(13,62); M2(13,98) = M1(13,63); M2(13,107) = M1(13,64); M2(13,108) = M1(13,65); M2(13,109) = M1(13,66); M2(13,110) = M1(13,67); M2(13,112) = M1(13,68); M2(13,113) = M1(13,69); M2(13,114) = M1(13,70); M2(13,116) = M1(13,71); M2(13,117) = M1(13,72); M2(13,119) = M1(13,73); M2(13,127) = M1(13,74); M2(13,128) = M1(13,75); M2(13,129) = M1(13,76); M2(13,131) = M1(13,77); M2(13,132) = M1(13,78); M2(13,134) = M1(13,79); M2(13,141) = M1(13,80); M2(13,142) = M1(13,81); M2(13,144) = M1(13,82); M2(13,150) = M1(13,83); M2(14,17) = M1(14,14); M2(14,18) = M1(14,15); M2(14,19) = M1(14,16); M2(14,20) = M1(14,17); M2(14,22) = M1(14,18); M2(14,23) = M1(14,19); M2(14,24) = M1(14,20); M2(14,25) = M1(14,21); M2(14,27) = M1(14,22); M2(14,28) = M1(14,23); M2(14,29) = M1(14,24); M2(14,31) = M1(14,25); M2(14,32) = M1(14,26); M2(14,34) = M1(14,27); M2(14,45) = M1(14,28); M2(14,46) = M1(14,29); M2(14,47) = M1(14,30); M2(14,48) = M1(14,31); M2(14,49) = M1(14,32); M2(14,50) = M1(14,33); M2(14,52) = M1(14,34); M2(14,53) = M1(14,35); M2(14,54) = M1(14,36); M2(14,55) = M1(14,37); M2(14,56) = M1(14,38); M2(14,58) = M1(14,39); M2(14,59) = M1(14,40); M2(14,60) = M1(14,41); M2(14,61) = M1(14,42); M2(14,63) = M1(14,43); M2(14,64) = M1(14,44); M2(14,65) = M1(14,45); M2(14,67) = M1(14,46); M2(14,68) = M1(14,47); M2(14,70) = M1(14,48); M2(14,79) = M1(14,49); M2(14,80) = M1(14,50); M2(14,81) = M1(14,51); M2(14,82) = M1(14,52); M2(14,83) = M1(14,53); M2(14,85) = M1(14,54); M2(14,86) = M1(14,55); M2(14,87) = M1(14,56); M2(14,88) = M1(14,57); M2(14,90) = M1(14,58); M2(14,91) = M1(14,59); M2(14,92) = M1(14,60); M2(14,95) = M1(14,61); M2(14,96) = M1(14,62); M2(14,98) = M1(14,63); M2(14,107) = M1(14,64); M2(14,108) = M1(14,65); M2(14,109) = M1(14,66); M2(14,110) = M1(14,67); M2(14,112) = M1(14,68); M2(14,113) = M1(14,69); M2(14,114) = M1(14,70); M2(14,116) = M1(14,71); M2(14,117) = M1(14,72); M2(14,119) = M1(14,73); M2(14,127) = M1(14,74); M2(14,128) = M1(14,75); M2(14,129) = M1(14,76); M2(14,131) = M1(14,77); M2(14,132) = M1(14,78); M2(14,134) = M1(14,79); M2(14,141) = M1(14,80); M2(14,142) = M1(14,81); M2(14,144) = M1(14,82); M2(14,150) = M1(14,83); M2(15,0) = M1(2,2); M2(15,12) = M1(2,15); M2(15,13) = M1(2,16); M2(15,14) = M1(2,17); M2(15,17) = M1(2,18); M2(15,18) = M1(2,19); M2(15,19) = M1(2,20); M2(15,20) = M1(2,21); M2(15,23) = M1(2,22); M2(15,24) = M1(2,23); M2(15,25) = M1(2,24); M2(15,28) = M1(2,25); M2(15,29) = M1(2,26); M2(15,32) = M1(2,27); M2(15,38) = M1(2,28); M2(15,39) = M1(2,29); M2(15,40) = M1(2,30); M2(15,41) = M1(2,31); M2(15,42) = M1(2,32); M2(15,43) = M1(2,33); M2(15,46) = M1(2,34); M2(15,47) = M1(2,35); M2(15,48) = M1(2,36); M2(15,49) = M1(2,37); M2(15,50) = M1(2,38); M2(15,53) = M1(2,39); M2(15,54) = M1(2,40); M2(15,55) = M1(2,41); M2(15,56) = M1(2,42); M2(15,59) = M1(2,43); M2(15,60) = M1(2,44); M2(15,61) = M1(2,45); M2(15,64) = M1(2,46); M2(15,65) = M1(2,47); M2(15,68) = M1(2,48); M2(15,73) = M1(2,49); M2(15,74) = M1(2,50); M2(15,75) = M1(2,51); M2(15,76) = M1(2,52); M2(15,77) = M1(2,53); M2(15,80) = M1(2,54); M2(15,81) = M1(2,55); M2(15,82) = M1(2,56); M2(15,83) = M1(2,57); M2(15,86) = M1(2,58); M2(15,87) = M1(2,59); M2(15,88) = M1(2,60); M2(15,91) = M1(2,61); M2(15,92) = M1(2,62); M2(15,96) = M1(2,63); M2(15,102) = M1(2,64); M2(15,103) = M1(2,65); M2(15,104) = M1(2,66); M2(15,105) = M1(2,67); M2(15,108) = M1(2,68); M2(15,109) = M1(2,69); M2(15,110) = M1(2,70); M2(15,113) = M1(2,71); M2(15,114) = M1(2,72); M2(15,117) = M1(2,73); M2(15,123) = M1(2,74); M2(15,124) = M1(2,75); M2(15,125) = M1(2,76); M2(15,128) = M1(2,77); M2(15,129) = M1(2,78); M2(15,132) = M1(2,79); M2(15,138) = M1(2,80); M2(15,139) = M1(2,81); M2(15,142) = M1(2,82); M2(15,148) = M1(2,83); M2(16,1) = M1(3,3); M2(16,12) = M1(3,15); M2(16,13) = M1(3,16); M2(16,14) = M1(3,17); M2(16,17) = M1(3,18); M2(16,18) = M1(3,19); M2(16,19) = M1(3,20); M2(16,20) = M1(3,21); M2(16,23) = M1(3,22); M2(16,24) = M1(3,23); M2(16,25) = M1(3,24); M2(16,28) = M1(3,25); M2(16,29) = M1(3,26); M2(16,32) = M1(3,27); M2(16,38) = M1(3,28); M2(16,39) = M1(3,29); M2(16,40) = M1(3,30); M2(16,41) = M1(3,31); M2(16,42) = M1(3,32); M2(16,43) = M1(3,33); M2(16,46) = M1(3,34); M2(16,47) = M1(3,35); M2(16,48) = M1(3,36); M2(16,49) = M1(3,37); M2(16,50) = M1(3,38); M2(16,53) = M1(3,39); M2(16,54) = M1(3,40); M2(16,55) = M1(3,41); M2(16,56) = M1(3,42); M2(16,59) = M1(3,43); M2(16,60) = M1(3,44); M2(16,61) = M1(3,45); M2(16,64) = M1(3,46); M2(16,65) = M1(3,47); M2(16,68) = M1(3,48); M2(16,73) = M1(3,49); M2(16,74) = M1(3,50); M2(16,75) = M1(3,51); M2(16,76) = M1(3,52); M2(16,77) = M1(3,53); M2(16,80) = M1(3,54); M2(16,81) = M1(3,55); M2(16,82) = M1(3,56); M2(16,83) = M1(3,57); M2(16,86) = M1(3,58); M2(16,87) = M1(3,59); M2(16,88) = M1(3,60); M2(16,91) = M1(3,61); M2(16,92) = M1(3,62); M2(16,96) = M1(3,63); M2(16,102) = M1(3,64); M2(16,103) = M1(3,65); M2(16,104) = M1(3,66); M2(16,105) = M1(3,67); M2(16,108) = M1(3,68); M2(16,109) = M1(3,69); M2(16,110) = M1(3,70); M2(16,113) = M1(3,71); M2(16,114) = M1(3,72); M2(16,117) = M1(3,73); M2(16,123) = M1(3,74); M2(16,124) = M1(3,75); M2(16,125) = M1(3,76); M2(16,128) = M1(3,77); M2(16,129) = M1(3,78); M2(16,132) = M1(3,79); M2(16,138) = M1(3,80); M2(16,139) = M1(3,81); M2(16,142) = M1(3,82); M2(16,148) = M1(3,83); M2(17,2) = M1(4,4); M2(17,12) = M1(4,15); M2(17,13) = M1(4,16); M2(17,14) = M1(4,17); M2(17,17) = M1(4,18); M2(17,18) = M1(4,19); M2(17,19) = M1(4,20); M2(17,20) = M1(4,21); M2(17,23) = M1(4,22); M2(17,24) = M1(4,23); M2(17,25) = M1(4,24); M2(17,28) = M1(4,25); M2(17,29) = M1(4,26); M2(17,32) = M1(4,27); M2(17,38) = M1(4,28); M2(17,39) = M1(4,29); M2(17,40) = M1(4,30); M2(17,41) = M1(4,31); M2(17,42) = M1(4,32); M2(17,43) = M1(4,33); M2(17,46) = M1(4,34); M2(17,47) = M1(4,35); M2(17,48) = M1(4,36); M2(17,49) = M1(4,37); M2(17,50) = M1(4,38); M2(17,53) = M1(4,39); M2(17,54) = M1(4,40); M2(17,55) = M1(4,41); M2(17,56) = M1(4,42); M2(17,59) = M1(4,43); M2(17,60) = M1(4,44); M2(17,61) = M1(4,45); M2(17,64) = M1(4,46); M2(17,65) = M1(4,47); M2(17,68) = M1(4,48); M2(17,73) = M1(4,49); M2(17,74) = M1(4,50); M2(17,75) = M1(4,51); M2(17,76) = M1(4,52); M2(17,77) = M1(4,53); M2(17,80) = M1(4,54); M2(17,81) = M1(4,55); M2(17,82) = M1(4,56); M2(17,83) = M1(4,57); M2(17,86) = M1(4,58); M2(17,87) = M1(4,59); M2(17,88) = M1(4,60); M2(17,91) = M1(4,61); M2(17,92) = M1(4,62); M2(17,96) = M1(4,63); M2(17,102) = M1(4,64); M2(17,103) = M1(4,65); M2(17,104) = M1(4,66); M2(17,105) = M1(4,67); M2(17,108) = M1(4,68); M2(17,109) = M1(4,69); M2(17,110) = M1(4,70); M2(17,113) = M1(4,71); M2(17,114) = M1(4,72); M2(17,117) = M1(4,73); M2(17,123) = M1(4,74); M2(17,124) = M1(4,75); M2(17,125) = M1(4,76); M2(17,128) = M1(4,77); M2(17,129) = M1(4,78); M2(17,132) = M1(4,79); M2(17,138) = M1(4,80); M2(17,139) = M1(4,81); M2(17,142) = M1(4,82); M2(17,148) = M1(4,83); M2(18,3) = M1(5,5); M2(18,12) = M1(5,15); M2(18,13) = M1(5,16); M2(18,14) = M1(5,17); M2(18,17) = M1(5,18); M2(18,18) = M1(5,19); M2(18,19) = M1(5,20); M2(18,20) = M1(5,21); M2(18,23) = M1(5,22); M2(18,24) = M1(5,23); M2(18,25) = M1(5,24); M2(18,28) = M1(5,25); M2(18,29) = M1(5,26); M2(18,32) = M1(5,27); M2(18,38) = M1(5,28); M2(18,39) = M1(5,29); M2(18,40) = M1(5,30); M2(18,41) = M1(5,31); M2(18,42) = M1(5,32); M2(18,43) = M1(5,33); M2(18,46) = M1(5,34); M2(18,47) = M1(5,35); M2(18,48) = M1(5,36); M2(18,49) = M1(5,37); M2(18,50) = M1(5,38); M2(18,53) = M1(5,39); M2(18,54) = M1(5,40); M2(18,55) = M1(5,41); M2(18,56) = M1(5,42); M2(18,59) = M1(5,43); M2(18,60) = M1(5,44); M2(18,61) = M1(5,45); M2(18,64) = M1(5,46); M2(18,65) = M1(5,47); M2(18,68) = M1(5,48); M2(18,73) = M1(5,49); M2(18,74) = M1(5,50); M2(18,75) = M1(5,51); M2(18,76) = M1(5,52); M2(18,77) = M1(5,53); M2(18,80) = M1(5,54); M2(18,81) = M1(5,55); M2(18,82) = M1(5,56); M2(18,83) = M1(5,57); M2(18,86) = M1(5,58); M2(18,87) = M1(5,59); M2(18,88) = M1(5,60); M2(18,91) = M1(5,61); M2(18,92) = M1(5,62); M2(18,96) = M1(5,63); M2(18,102) = M1(5,64); M2(18,103) = M1(5,65); M2(18,104) = M1(5,66); M2(18,105) = M1(5,67); M2(18,108) = M1(5,68); M2(18,109) = M1(5,69); M2(18,110) = M1(5,70); M2(18,113) = M1(5,71); M2(18,114) = M1(5,72); M2(18,117) = M1(5,73); M2(18,123) = M1(5,74); M2(18,124) = M1(5,75); M2(18,125) = M1(5,76); M2(18,128) = M1(5,77); M2(18,129) = M1(5,78); M2(18,132) = M1(5,79); M2(18,138) = M1(5,80); M2(18,139) = M1(5,81); M2(18,142) = M1(5,82); M2(18,148) = M1(5,83); M2(19,4) = M1(7,7); M2(19,12) = M1(7,15); M2(19,13) = M1(7,16); M2(19,14) = M1(7,17); M2(19,17) = M1(7,18); M2(19,18) = M1(7,19); M2(19,19) = M1(7,20); M2(19,20) = M1(7,21); M2(19,23) = M1(7,22); M2(19,24) = M1(7,23); M2(19,25) = M1(7,24); M2(19,28) = M1(7,25); M2(19,29) = M1(7,26); M2(19,32) = M1(7,27); M2(19,38) = M1(7,28); M2(19,39) = M1(7,29); M2(19,40) = M1(7,30); M2(19,41) = M1(7,31); M2(19,42) = M1(7,32); M2(19,43) = M1(7,33); M2(19,46) = M1(7,34); M2(19,47) = M1(7,35); M2(19,48) = M1(7,36); M2(19,49) = M1(7,37); M2(19,50) = M1(7,38); M2(19,53) = M1(7,39); M2(19,54) = M1(7,40); M2(19,55) = M1(7,41); M2(19,56) = M1(7,42); M2(19,59) = M1(7,43); M2(19,60) = M1(7,44); M2(19,61) = M1(7,45); M2(19,64) = M1(7,46); M2(19,65) = M1(7,47); M2(19,68) = M1(7,48); M2(19,73) = M1(7,49); M2(19,74) = M1(7,50); M2(19,75) = M1(7,51); M2(19,76) = M1(7,52); M2(19,77) = M1(7,53); M2(19,80) = M1(7,54); M2(19,81) = M1(7,55); M2(19,82) = M1(7,56); M2(19,83) = M1(7,57); M2(19,86) = M1(7,58); M2(19,87) = M1(7,59); M2(19,88) = M1(7,60); M2(19,91) = M1(7,61); M2(19,92) = M1(7,62); M2(19,96) = M1(7,63); M2(19,102) = M1(7,64); M2(19,103) = M1(7,65); M2(19,104) = M1(7,66); M2(19,105) = M1(7,67); M2(19,108) = M1(7,68); M2(19,109) = M1(7,69); M2(19,110) = M1(7,70); M2(19,113) = M1(7,71); M2(19,114) = M1(7,72); M2(19,117) = M1(7,73); M2(19,123) = M1(7,74); M2(19,124) = M1(7,75); M2(19,125) = M1(7,76); M2(19,128) = M1(7,77); M2(19,129) = M1(7,78); M2(19,132) = M1(7,79); M2(19,138) = M1(7,80); M2(19,139) = M1(7,81); M2(19,142) = M1(7,82); M2(19,148) = M1(7,83); M2(20,5) = M1(8,8); M2(20,12) = M1(8,15); M2(20,13) = M1(8,16); M2(20,14) = M1(8,17); M2(20,17) = M1(8,18); M2(20,18) = M1(8,19); M2(20,19) = M1(8,20); M2(20,20) = M1(8,21); M2(20,23) = M1(8,22); M2(20,24) = M1(8,23); M2(20,25) = M1(8,24); M2(20,28) = M1(8,25); M2(20,29) = M1(8,26); M2(20,32) = M1(8,27); M2(20,38) = M1(8,28); M2(20,39) = M1(8,29); M2(20,40) = M1(8,30); M2(20,41) = M1(8,31); M2(20,42) = M1(8,32); M2(20,43) = M1(8,33); M2(20,46) = M1(8,34); M2(20,47) = M1(8,35); M2(20,48) = M1(8,36); M2(20,49) = M1(8,37); M2(20,50) = M1(8,38); M2(20,53) = M1(8,39); M2(20,54) = M1(8,40); M2(20,55) = M1(8,41); M2(20,56) = M1(8,42); M2(20,59) = M1(8,43); M2(20,60) = M1(8,44); M2(20,61) = M1(8,45); M2(20,64) = M1(8,46); M2(20,65) = M1(8,47); M2(20,68) = M1(8,48); M2(20,73) = M1(8,49); M2(20,74) = M1(8,50); M2(20,75) = M1(8,51); M2(20,76) = M1(8,52); M2(20,77) = M1(8,53); M2(20,80) = M1(8,54); M2(20,81) = M1(8,55); M2(20,82) = M1(8,56); M2(20,83) = M1(8,57); M2(20,86) = M1(8,58); M2(20,87) = M1(8,59); M2(20,88) = M1(8,60); M2(20,91) = M1(8,61); M2(20,92) = M1(8,62); M2(20,96) = M1(8,63); M2(20,102) = M1(8,64); M2(20,103) = M1(8,65); M2(20,104) = M1(8,66); M2(20,105) = M1(8,67); M2(20,108) = M1(8,68); M2(20,109) = M1(8,69); M2(20,110) = M1(8,70); M2(20,113) = M1(8,71); M2(20,114) = M1(8,72); M2(20,117) = M1(8,73); M2(20,123) = M1(8,74); M2(20,124) = M1(8,75); M2(20,125) = M1(8,76); M2(20,128) = M1(8,77); M2(20,129) = M1(8,78); M2(20,132) = M1(8,79); M2(20,138) = M1(8,80); M2(20,139) = M1(8,81); M2(20,142) = M1(8,82); M2(20,148) = M1(8,83); M2(21,6) = M1(9,9); M2(21,12) = M1(9,15); M2(21,13) = M1(9,16); M2(21,14) = M1(9,17); M2(21,17) = M1(9,18); M2(21,18) = M1(9,19); M2(21,19) = M1(9,20); M2(21,20) = M1(9,21); M2(21,23) = M1(9,22); M2(21,24) = M1(9,23); M2(21,25) = M1(9,24); M2(21,28) = M1(9,25); M2(21,29) = M1(9,26); M2(21,32) = M1(9,27); M2(21,38) = M1(9,28); M2(21,39) = M1(9,29); M2(21,40) = M1(9,30); M2(21,41) = M1(9,31); M2(21,42) = M1(9,32); M2(21,43) = M1(9,33); M2(21,46) = M1(9,34); M2(21,47) = M1(9,35); M2(21,48) = M1(9,36); M2(21,49) = M1(9,37); M2(21,50) = M1(9,38); M2(21,53) = M1(9,39); M2(21,54) = M1(9,40); M2(21,55) = M1(9,41); M2(21,56) = M1(9,42); M2(21,59) = M1(9,43); M2(21,60) = M1(9,44); M2(21,61) = M1(9,45); M2(21,64) = M1(9,46); M2(21,65) = M1(9,47); M2(21,68) = M1(9,48); M2(21,73) = M1(9,49); M2(21,74) = M1(9,50); M2(21,75) = M1(9,51); M2(21,76) = M1(9,52); M2(21,77) = M1(9,53); M2(21,80) = M1(9,54); M2(21,81) = M1(9,55); M2(21,82) = M1(9,56); M2(21,83) = M1(9,57); M2(21,86) = M1(9,58); M2(21,87) = M1(9,59); M2(21,88) = M1(9,60); M2(21,91) = M1(9,61); M2(21,92) = M1(9,62); M2(21,96) = M1(9,63); M2(21,102) = M1(9,64); M2(21,103) = M1(9,65); M2(21,104) = M1(9,66); M2(21,105) = M1(9,67); M2(21,108) = M1(9,68); M2(21,109) = M1(9,69); M2(21,110) = M1(9,70); M2(21,113) = M1(9,71); M2(21,114) = M1(9,72); M2(21,117) = M1(9,73); M2(21,123) = M1(9,74); M2(21,124) = M1(9,75); M2(21,125) = M1(9,76); M2(21,128) = M1(9,77); M2(21,129) = M1(9,78); M2(21,132) = M1(9,79); M2(21,138) = M1(9,80); M2(21,139) = M1(9,81); M2(21,142) = M1(9,82); M2(21,148) = M1(9,83); M2(22,7) = M1(10,10); M2(22,12) = M1(10,15); M2(22,13) = M1(10,16); M2(22,14) = M1(10,17); M2(22,17) = M1(10,18); M2(22,18) = M1(10,19); M2(22,19) = M1(10,20); M2(22,20) = M1(10,21); M2(22,23) = M1(10,22); M2(22,24) = M1(10,23); M2(22,25) = M1(10,24); M2(22,28) = M1(10,25); M2(22,29) = M1(10,26); M2(22,32) = M1(10,27); M2(22,38) = M1(10,28); M2(22,39) = M1(10,29); M2(22,40) = M1(10,30); M2(22,41) = M1(10,31); M2(22,42) = M1(10,32); M2(22,43) = M1(10,33); M2(22,46) = M1(10,34); M2(22,47) = M1(10,35); M2(22,48) = M1(10,36); M2(22,49) = M1(10,37); M2(22,50) = M1(10,38); M2(22,53) = M1(10,39); M2(22,54) = M1(10,40); M2(22,55) = M1(10,41); M2(22,56) = M1(10,42); M2(22,59) = M1(10,43); M2(22,60) = M1(10,44); M2(22,61) = M1(10,45); M2(22,64) = M1(10,46); M2(22,65) = M1(10,47); M2(22,68) = M1(10,48); M2(22,73) = M1(10,49); M2(22,74) = M1(10,50); M2(22,75) = M1(10,51); M2(22,76) = M1(10,52); M2(22,77) = M1(10,53); M2(22,80) = M1(10,54); M2(22,81) = M1(10,55); M2(22,82) = M1(10,56); M2(22,83) = M1(10,57); M2(22,86) = M1(10,58); M2(22,87) = M1(10,59); M2(22,88) = M1(10,60); M2(22,91) = M1(10,61); M2(22,92) = M1(10,62); M2(22,96) = M1(10,63); M2(22,102) = M1(10,64); M2(22,103) = M1(10,65); M2(22,104) = M1(10,66); M2(22,105) = M1(10,67); M2(22,108) = M1(10,68); M2(22,109) = M1(10,69); M2(22,110) = M1(10,70); M2(22,113) = M1(10,71); M2(22,114) = M1(10,72); M2(22,117) = M1(10,73); M2(22,123) = M1(10,74); M2(22,124) = M1(10,75); M2(22,125) = M1(10,76); M2(22,128) = M1(10,77); M2(22,129) = M1(10,78); M2(22,132) = M1(10,79); M2(22,138) = M1(10,80); M2(22,139) = M1(10,81); M2(22,142) = M1(10,82); M2(22,148) = M1(10,83); M2(23,8) = M1(11,11); M2(23,12) = M1(11,15); M2(23,13) = M1(11,16); M2(23,14) = M1(11,17); M2(23,17) = M1(11,18); M2(23,18) = M1(11,19); M2(23,19) = M1(11,20); M2(23,20) = M1(11,21); M2(23,23) = M1(11,22); M2(23,24) = M1(11,23); M2(23,25) = M1(11,24); M2(23,28) = M1(11,25); M2(23,29) = M1(11,26); M2(23,32) = M1(11,27); M2(23,38) = M1(11,28); M2(23,39) = M1(11,29); M2(23,40) = M1(11,30); M2(23,41) = M1(11,31); M2(23,42) = M1(11,32); M2(23,43) = M1(11,33); M2(23,46) = M1(11,34); M2(23,47) = M1(11,35); M2(23,48) = M1(11,36); M2(23,49) = M1(11,37); M2(23,50) = M1(11,38); M2(23,53) = M1(11,39); M2(23,54) = M1(11,40); M2(23,55) = M1(11,41); M2(23,56) = M1(11,42); M2(23,59) = M1(11,43); M2(23,60) = M1(11,44); M2(23,61) = M1(11,45); M2(23,64) = M1(11,46); M2(23,65) = M1(11,47); M2(23,68) = M1(11,48); M2(23,73) = M1(11,49); M2(23,74) = M1(11,50); M2(23,75) = M1(11,51); M2(23,76) = M1(11,52); M2(23,77) = M1(11,53); M2(23,80) = M1(11,54); M2(23,81) = M1(11,55); M2(23,82) = M1(11,56); M2(23,83) = M1(11,57); M2(23,86) = M1(11,58); M2(23,87) = M1(11,59); M2(23,88) = M1(11,60); M2(23,91) = M1(11,61); M2(23,92) = M1(11,62); M2(23,96) = M1(11,63); M2(23,102) = M1(11,64); M2(23,103) = M1(11,65); M2(23,104) = M1(11,66); M2(23,105) = M1(11,67); M2(23,108) = M1(11,68); M2(23,109) = M1(11,69); M2(23,110) = M1(11,70); M2(23,113) = M1(11,71); M2(23,114) = M1(11,72); M2(23,117) = M1(11,73); M2(23,123) = M1(11,74); M2(23,124) = M1(11,75); M2(23,125) = M1(11,76); M2(23,128) = M1(11,77); M2(23,129) = M1(11,78); M2(23,132) = M1(11,79); M2(23,138) = M1(11,80); M2(23,139) = M1(11,81); M2(23,142) = M1(11,82); M2(23,148) = M1(11,83); M2(24,9) = M1(12,12); M2(24,12) = M1(12,15); M2(24,13) = M1(12,16); M2(24,14) = M1(12,17); M2(24,17) = M1(12,18); M2(24,18) = M1(12,19); M2(24,19) = M1(12,20); M2(24,20) = M1(12,21); M2(24,23) = M1(12,22); M2(24,24) = M1(12,23); M2(24,25) = M1(12,24); M2(24,28) = M1(12,25); M2(24,29) = M1(12,26); M2(24,32) = M1(12,27); M2(24,38) = M1(12,28); M2(24,39) = M1(12,29); M2(24,40) = M1(12,30); M2(24,41) = M1(12,31); M2(24,42) = M1(12,32); M2(24,43) = M1(12,33); M2(24,46) = M1(12,34); M2(24,47) = M1(12,35); M2(24,48) = M1(12,36); M2(24,49) = M1(12,37); M2(24,50) = M1(12,38); M2(24,53) = M1(12,39); M2(24,54) = M1(12,40); M2(24,55) = M1(12,41); M2(24,56) = M1(12,42); M2(24,59) = M1(12,43); M2(24,60) = M1(12,44); M2(24,61) = M1(12,45); M2(24,64) = M1(12,46); M2(24,65) = M1(12,47); M2(24,68) = M1(12,48); M2(24,73) = M1(12,49); M2(24,74) = M1(12,50); M2(24,75) = M1(12,51); M2(24,76) = M1(12,52); M2(24,77) = M1(12,53); M2(24,80) = M1(12,54); M2(24,81) = M1(12,55); M2(24,82) = M1(12,56); M2(24,83) = M1(12,57); M2(24,86) = M1(12,58); M2(24,87) = M1(12,59); M2(24,88) = M1(12,60); M2(24,91) = M1(12,61); M2(24,92) = M1(12,62); M2(24,96) = M1(12,63); M2(24,102) = M1(12,64); M2(24,103) = M1(12,65); M2(24,104) = M1(12,66); M2(24,105) = M1(12,67); M2(24,108) = M1(12,68); M2(24,109) = M1(12,69); M2(24,110) = M1(12,70); M2(24,113) = M1(12,71); M2(24,114) = M1(12,72); M2(24,117) = M1(12,73); M2(24,123) = M1(12,74); M2(24,124) = M1(12,75); M2(24,125) = M1(12,76); M2(24,128) = M1(12,77); M2(24,129) = M1(12,78); M2(24,132) = M1(12,79); M2(24,138) = M1(12,80); M2(24,139) = M1(12,81); M2(24,142) = M1(12,82); M2(24,148) = M1(12,83); M2(25,10) = M1(13,13); M2(25,12) = M1(13,15); M2(25,13) = M1(13,16); M2(25,14) = M1(13,17); M2(25,17) = M1(13,18); M2(25,18) = M1(13,19); M2(25,19) = M1(13,20); M2(25,20) = M1(13,21); M2(25,23) = M1(13,22); M2(25,24) = M1(13,23); M2(25,25) = M1(13,24); M2(25,28) = M1(13,25); M2(25,29) = M1(13,26); M2(25,32) = M1(13,27); M2(25,38) = M1(13,28); M2(25,39) = M1(13,29); M2(25,40) = M1(13,30); M2(25,41) = M1(13,31); M2(25,42) = M1(13,32); M2(25,43) = M1(13,33); M2(25,46) = M1(13,34); M2(25,47) = M1(13,35); M2(25,48) = M1(13,36); M2(25,49) = M1(13,37); M2(25,50) = M1(13,38); M2(25,53) = M1(13,39); M2(25,54) = M1(13,40); M2(25,55) = M1(13,41); M2(25,56) = M1(13,42); M2(25,59) = M1(13,43); M2(25,60) = M1(13,44); M2(25,61) = M1(13,45); M2(25,64) = M1(13,46); M2(25,65) = M1(13,47); M2(25,68) = M1(13,48); M2(25,73) = M1(13,49); M2(25,74) = M1(13,50); M2(25,75) = M1(13,51); M2(25,76) = M1(13,52); M2(25,77) = M1(13,53); M2(25,80) = M1(13,54); M2(25,81) = M1(13,55); M2(25,82) = M1(13,56); M2(25,83) = M1(13,57); M2(25,86) = M1(13,58); M2(25,87) = M1(13,59); M2(25,88) = M1(13,60); M2(25,91) = M1(13,61); M2(25,92) = M1(13,62); M2(25,96) = M1(13,63); M2(25,102) = M1(13,64); M2(25,103) = M1(13,65); M2(25,104) = M1(13,66); M2(25,105) = M1(13,67); M2(25,108) = M1(13,68); M2(25,109) = M1(13,69); M2(25,110) = M1(13,70); M2(25,113) = M1(13,71); M2(25,114) = M1(13,72); M2(25,117) = M1(13,73); M2(25,123) = M1(13,74); M2(25,124) = M1(13,75); M2(25,125) = M1(13,76); M2(25,128) = M1(13,77); M2(25,129) = M1(13,78); M2(25,132) = M1(13,79); M2(25,138) = M1(13,80); M2(25,139) = M1(13,81); M2(25,142) = M1(13,82); M2(25,148) = M1(13,83); M2(26,11) = M1(14,14); M2(26,12) = M1(14,15); M2(26,13) = M1(14,16); M2(26,14) = M1(14,17); M2(26,17) = M1(14,18); M2(26,18) = M1(14,19); M2(26,19) = M1(14,20); M2(26,20) = M1(14,21); M2(26,23) = M1(14,22); M2(26,24) = M1(14,23); M2(26,25) = M1(14,24); M2(26,28) = M1(14,25); M2(26,29) = M1(14,26); M2(26,32) = M1(14,27); M2(26,38) = M1(14,28); M2(26,39) = M1(14,29); M2(26,40) = M1(14,30); M2(26,41) = M1(14,31); M2(26,42) = M1(14,32); M2(26,43) = M1(14,33); M2(26,46) = M1(14,34); M2(26,47) = M1(14,35); M2(26,48) = M1(14,36); M2(26,49) = M1(14,37); M2(26,50) = M1(14,38); M2(26,53) = M1(14,39); M2(26,54) = M1(14,40); M2(26,55) = M1(14,41); M2(26,56) = M1(14,42); M2(26,59) = M1(14,43); M2(26,60) = M1(14,44); M2(26,61) = M1(14,45); M2(26,64) = M1(14,46); M2(26,65) = M1(14,47); M2(26,68) = M1(14,48); M2(26,73) = M1(14,49); M2(26,74) = M1(14,50); M2(26,75) = M1(14,51); M2(26,76) = M1(14,52); M2(26,77) = M1(14,53); M2(26,80) = M1(14,54); M2(26,81) = M1(14,55); M2(26,82) = M1(14,56); M2(26,83) = M1(14,57); M2(26,86) = M1(14,58); M2(26,87) = M1(14,59); M2(26,88) = M1(14,60); M2(26,91) = M1(14,61); M2(26,92) = M1(14,62); M2(26,96) = M1(14,63); M2(26,102) = M1(14,64); M2(26,103) = M1(14,65); M2(26,104) = M1(14,66); M2(26,105) = M1(14,67); M2(26,108) = M1(14,68); M2(26,109) = M1(14,69); M2(26,110) = M1(14,70); M2(26,113) = M1(14,71); M2(26,114) = M1(14,72); M2(26,117) = M1(14,73); M2(26,123) = M1(14,74); M2(26,124) = M1(14,75); M2(26,125) = M1(14,76); M2(26,128) = M1(14,77); M2(26,129) = M1(14,78); M2(26,132) = M1(14,79); M2(26,138) = M1(14,80); M2(26,139) = M1(14,81); M2(26,142) = M1(14,82); M2(26,148) = M1(14,83); M2(27,0) = M1(3,3); M2(27,11) = M1(3,15); M2(27,12) = M1(3,16); M2(27,13) = M1(3,17); M2(27,16) = M1(3,18); M2(27,17) = M1(3,19); M2(27,18) = M1(3,20); M2(27,19) = M1(3,21); M2(27,22) = M1(3,22); M2(27,23) = M1(3,23); M2(27,24) = M1(3,24); M2(27,27) = M1(3,25); M2(27,28) = M1(3,26); M2(27,31) = M1(3,27); M2(27,37) = M1(3,28); M2(27,38) = M1(3,29); M2(27,39) = M1(3,30); M2(27,40) = M1(3,31); M2(27,41) = M1(3,32); M2(27,42) = M1(3,33); M2(27,45) = M1(3,34); M2(27,46) = M1(3,35); M2(27,47) = M1(3,36); M2(27,48) = M1(3,37); M2(27,49) = M1(3,38); M2(27,52) = M1(3,39); M2(27,53) = M1(3,40); M2(27,54) = M1(3,41); M2(27,55) = M1(3,42); M2(27,58) = M1(3,43); M2(27,59) = M1(3,44); M2(27,60) = M1(3,45); M2(27,63) = M1(3,46); M2(27,64) = M1(3,47); M2(27,67) = M1(3,48); M2(27,72) = M1(3,49); M2(27,73) = M1(3,50); M2(27,74) = M1(3,51); M2(27,75) = M1(3,52); M2(27,76) = M1(3,53); M2(27,79) = M1(3,54); M2(27,80) = M1(3,55); M2(27,81) = M1(3,56); M2(27,82) = M1(3,57); M2(27,85) = M1(3,58); M2(27,86) = M1(3,59); M2(27,87) = M1(3,60); M2(27,90) = M1(3,61); M2(27,91) = M1(3,62); M2(27,95) = M1(3,63); M2(27,101) = M1(3,64); M2(27,102) = M1(3,65); M2(27,103) = M1(3,66); M2(27,104) = M1(3,67); M2(27,107) = M1(3,68); M2(27,108) = M1(3,69); M2(27,109) = M1(3,70); M2(27,112) = M1(3,71); M2(27,113) = M1(3,72); M2(27,116) = M1(3,73); M2(27,122) = M1(3,74); M2(27,123) = M1(3,75); M2(27,124) = M1(3,76); M2(27,127) = M1(3,77); M2(27,128) = M1(3,78); M2(27,131) = M1(3,79); M2(27,137) = M1(3,80); M2(27,138) = M1(3,81); M2(27,141) = M1(3,82); M2(27,147) = M1(3,83); M2(28,1) = M1(4,4); M2(28,11) = M1(4,15); M2(28,12) = M1(4,16); M2(28,13) = M1(4,17); M2(28,16) = M1(4,18); M2(28,17) = M1(4,19); M2(28,18) = M1(4,20); M2(28,19) = M1(4,21); M2(28,22) = M1(4,22); M2(28,23) = M1(4,23); M2(28,24) = M1(4,24); M2(28,27) = M1(4,25); M2(28,28) = M1(4,26); M2(28,31) = M1(4,27); M2(28,37) = M1(4,28); M2(28,38) = M1(4,29); M2(28,39) = M1(4,30); M2(28,40) = M1(4,31); M2(28,41) = M1(4,32); M2(28,42) = M1(4,33); M2(28,45) = M1(4,34); M2(28,46) = M1(4,35); M2(28,47) = M1(4,36); M2(28,48) = M1(4,37); M2(28,49) = M1(4,38); M2(28,52) = M1(4,39); M2(28,53) = M1(4,40); M2(28,54) = M1(4,41); M2(28,55) = M1(4,42); M2(28,58) = M1(4,43); M2(28,59) = M1(4,44); M2(28,60) = M1(4,45); M2(28,63) = M1(4,46); M2(28,64) = M1(4,47); M2(28,67) = M1(4,48); M2(28,72) = M1(4,49); M2(28,73) = M1(4,50); M2(28,74) = M1(4,51); M2(28,75) = M1(4,52); M2(28,76) = M1(4,53); M2(28,79) = M1(4,54); M2(28,80) = M1(4,55); M2(28,81) = M1(4,56); M2(28,82) = M1(4,57); M2(28,85) = M1(4,58); M2(28,86) = M1(4,59); M2(28,87) = M1(4,60); M2(28,90) = M1(4,61); M2(28,91) = M1(4,62); M2(28,95) = M1(4,63); M2(28,101) = M1(4,64); M2(28,102) = M1(4,65); M2(28,103) = M1(4,66); M2(28,104) = M1(4,67); M2(28,107) = M1(4,68); M2(28,108) = M1(4,69); M2(28,109) = M1(4,70); M2(28,112) = M1(4,71); M2(28,113) = M1(4,72); M2(28,116) = M1(4,73); M2(28,122) = M1(4,74); M2(28,123) = M1(4,75); M2(28,124) = M1(4,76); M2(28,127) = M1(4,77); M2(28,128) = M1(4,78); M2(28,131) = M1(4,79); M2(28,137) = M1(4,80); M2(28,138) = M1(4,81); M2(28,141) = M1(4,82); M2(28,147) = M1(4,83); M2(29,2) = M1(5,5); M2(29,11) = M1(5,15); M2(29,12) = M1(5,16); M2(29,13) = M1(5,17); M2(29,16) = M1(5,18); M2(29,17) = M1(5,19); M2(29,18) = M1(5,20); M2(29,19) = M1(5,21); M2(29,22) = M1(5,22); M2(29,23) = M1(5,23); M2(29,24) = M1(5,24); M2(29,27) = M1(5,25); M2(29,28) = M1(5,26); M2(29,31) = M1(5,27); M2(29,37) = M1(5,28); M2(29,38) = M1(5,29); M2(29,39) = M1(5,30); M2(29,40) = M1(5,31); M2(29,41) = M1(5,32); M2(29,42) = M1(5,33); M2(29,45) = M1(5,34); M2(29,46) = M1(5,35); M2(29,47) = M1(5,36); M2(29,48) = M1(5,37); M2(29,49) = M1(5,38); M2(29,52) = M1(5,39); M2(29,53) = M1(5,40); M2(29,54) = M1(5,41); M2(29,55) = M1(5,42); M2(29,58) = M1(5,43); M2(29,59) = M1(5,44); M2(29,60) = M1(5,45); M2(29,63) = M1(5,46); M2(29,64) = M1(5,47); M2(29,67) = M1(5,48); M2(29,72) = M1(5,49); M2(29,73) = M1(5,50); M2(29,74) = M1(5,51); M2(29,75) = M1(5,52); M2(29,76) = M1(5,53); M2(29,79) = M1(5,54); M2(29,80) = M1(5,55); M2(29,81) = M1(5,56); M2(29,82) = M1(5,57); M2(29,85) = M1(5,58); M2(29,86) = M1(5,59); M2(29,87) = M1(5,60); M2(29,90) = M1(5,61); M2(29,91) = M1(5,62); M2(29,95) = M1(5,63); M2(29,101) = M1(5,64); M2(29,102) = M1(5,65); M2(29,103) = M1(5,66); M2(29,104) = M1(5,67); M2(29,107) = M1(5,68); M2(29,108) = M1(5,69); M2(29,109) = M1(5,70); M2(29,112) = M1(5,71); M2(29,113) = M1(5,72); M2(29,116) = M1(5,73); M2(29,122) = M1(5,74); M2(29,123) = M1(5,75); M2(29,124) = M1(5,76); M2(29,127) = M1(5,77); M2(29,128) = M1(5,78); M2(29,131) = M1(5,79); M2(29,137) = M1(5,80); M2(29,138) = M1(5,81); M2(29,141) = M1(5,82); M2(29,147) = M1(5,83); M2(30,3) = M1(6,6); M2(30,11) = M1(6,15); M2(30,12) = M1(6,16); M2(30,13) = M1(6,17); M2(30,16) = M1(6,18); M2(30,17) = M1(6,19); M2(30,18) = M1(6,20); M2(30,19) = M1(6,21); M2(30,22) = M1(6,22); M2(30,23) = M1(6,23); M2(30,24) = M1(6,24); M2(30,27) = M1(6,25); M2(30,28) = M1(6,26); M2(30,31) = M1(6,27); M2(30,37) = M1(6,28); M2(30,38) = M1(6,29); M2(30,39) = M1(6,30); M2(30,40) = M1(6,31); M2(30,41) = M1(6,32); M2(30,42) = M1(6,33); M2(30,45) = M1(6,34); M2(30,46) = M1(6,35); M2(30,47) = M1(6,36); M2(30,48) = M1(6,37); M2(30,49) = M1(6,38); M2(30,52) = M1(6,39); M2(30,53) = M1(6,40); M2(30,54) = M1(6,41); M2(30,55) = M1(6,42); M2(30,58) = M1(6,43); M2(30,59) = M1(6,44); M2(30,60) = M1(6,45); M2(30,63) = M1(6,46); M2(30,64) = M1(6,47); M2(30,67) = M1(6,48); M2(30,72) = M1(6,49); M2(30,73) = M1(6,50); M2(30,74) = M1(6,51); M2(30,75) = M1(6,52); M2(30,76) = M1(6,53); M2(30,79) = M1(6,54); M2(30,80) = M1(6,55); M2(30,81) = M1(6,56); M2(30,82) = M1(6,57); M2(30,85) = M1(6,58); M2(30,86) = M1(6,59); M2(30,87) = M1(6,60); M2(30,90) = M1(6,61); M2(30,91) = M1(6,62); M2(30,95) = M1(6,63); M2(30,101) = M1(6,64); M2(30,102) = M1(6,65); M2(30,103) = M1(6,66); M2(30,104) = M1(6,67); M2(30,107) = M1(6,68); M2(30,108) = M1(6,69); M2(30,109) = M1(6,70); M2(30,112) = M1(6,71); M2(30,113) = M1(6,72); M2(30,116) = M1(6,73); M2(30,122) = M1(6,74); M2(30,123) = M1(6,75); M2(30,124) = M1(6,76); M2(30,127) = M1(6,77); M2(30,128) = M1(6,78); M2(30,131) = M1(6,79); M2(30,137) = M1(6,80); M2(30,138) = M1(6,81); M2(30,141) = M1(6,82); M2(30,147) = M1(6,83); M2(31,4) = M1(8,8); M2(31,11) = M1(8,15); M2(31,12) = M1(8,16); M2(31,13) = M1(8,17); M2(31,16) = M1(8,18); M2(31,17) = M1(8,19); M2(31,18) = M1(8,20); M2(31,19) = M1(8,21); M2(31,22) = M1(8,22); M2(31,23) = M1(8,23); M2(31,24) = M1(8,24); M2(31,27) = M1(8,25); M2(31,28) = M1(8,26); M2(31,31) = M1(8,27); M2(31,37) = M1(8,28); M2(31,38) = M1(8,29); M2(31,39) = M1(8,30); M2(31,40) = M1(8,31); M2(31,41) = M1(8,32); M2(31,42) = M1(8,33); M2(31,45) = M1(8,34); M2(31,46) = M1(8,35); M2(31,47) = M1(8,36); M2(31,48) = M1(8,37); M2(31,49) = M1(8,38); M2(31,52) = M1(8,39); M2(31,53) = M1(8,40); M2(31,54) = M1(8,41); M2(31,55) = M1(8,42); M2(31,58) = M1(8,43); M2(31,59) = M1(8,44); M2(31,60) = M1(8,45); M2(31,63) = M1(8,46); M2(31,64) = M1(8,47); M2(31,67) = M1(8,48); M2(31,72) = M1(8,49); M2(31,73) = M1(8,50); M2(31,74) = M1(8,51); M2(31,75) = M1(8,52); M2(31,76) = M1(8,53); M2(31,79) = M1(8,54); M2(31,80) = M1(8,55); M2(31,81) = M1(8,56); M2(31,82) = M1(8,57); M2(31,85) = M1(8,58); M2(31,86) = M1(8,59); M2(31,87) = M1(8,60); M2(31,90) = M1(8,61); M2(31,91) = M1(8,62); M2(31,95) = M1(8,63); M2(31,101) = M1(8,64); M2(31,102) = M1(8,65); M2(31,103) = M1(8,66); M2(31,104) = M1(8,67); M2(31,107) = M1(8,68); M2(31,108) = M1(8,69); M2(31,109) = M1(8,70); M2(31,112) = M1(8,71); M2(31,113) = M1(8,72); M2(31,116) = M1(8,73); M2(31,122) = M1(8,74); M2(31,123) = M1(8,75); M2(31,124) = M1(8,76); M2(31,127) = M1(8,77); M2(31,128) = M1(8,78); M2(31,131) = M1(8,79); M2(31,137) = M1(8,80); M2(31,138) = M1(8,81); M2(31,141) = M1(8,82); M2(31,147) = M1(8,83); M2(32,5) = M1(9,9); M2(32,11) = M1(9,15); M2(32,12) = M1(9,16); M2(32,13) = M1(9,17); M2(32,16) = M1(9,18); M2(32,17) = M1(9,19); M2(32,18) = M1(9,20); M2(32,19) = M1(9,21); M2(32,22) = M1(9,22); M2(32,23) = M1(9,23); M2(32,24) = M1(9,24); M2(32,27) = M1(9,25); M2(32,28) = M1(9,26); M2(32,31) = M1(9,27); M2(32,37) = M1(9,28); M2(32,38) = M1(9,29); M2(32,39) = M1(9,30); M2(32,40) = M1(9,31); M2(32,41) = M1(9,32); M2(32,42) = M1(9,33); M2(32,45) = M1(9,34); M2(32,46) = M1(9,35); M2(32,47) = M1(9,36); M2(32,48) = M1(9,37); M2(32,49) = M1(9,38); M2(32,52) = M1(9,39); M2(32,53) = M1(9,40); M2(32,54) = M1(9,41); M2(32,55) = M1(9,42); M2(32,58) = M1(9,43); M2(32,59) = M1(9,44); M2(32,60) = M1(9,45); M2(32,63) = M1(9,46); M2(32,64) = M1(9,47); M2(32,67) = M1(9,48); M2(32,72) = M1(9,49); M2(32,73) = M1(9,50); M2(32,74) = M1(9,51); M2(32,75) = M1(9,52); M2(32,76) = M1(9,53); M2(32,79) = M1(9,54); M2(32,80) = M1(9,55); M2(32,81) = M1(9,56); M2(32,82) = M1(9,57); M2(32,85) = M1(9,58); M2(32,86) = M1(9,59); M2(32,87) = M1(9,60); M2(32,90) = M1(9,61); M2(32,91) = M1(9,62); M2(32,95) = M1(9,63); M2(32,101) = M1(9,64); M2(32,102) = M1(9,65); M2(32,103) = M1(9,66); M2(32,104) = M1(9,67); M2(32,107) = M1(9,68); M2(32,108) = M1(9,69); M2(32,109) = M1(9,70); M2(32,112) = M1(9,71); M2(32,113) = M1(9,72); M2(32,116) = M1(9,73); M2(32,122) = M1(9,74); M2(32,123) = M1(9,75); M2(32,124) = M1(9,76); M2(32,127) = M1(9,77); M2(32,128) = M1(9,78); M2(32,131) = M1(9,79); M2(32,137) = M1(9,80); M2(32,138) = M1(9,81); M2(32,141) = M1(9,82); M2(32,147) = M1(9,83); M2(33,6) = M1(10,10); M2(33,11) = M1(10,15); M2(33,12) = M1(10,16); M2(33,13) = M1(10,17); M2(33,16) = M1(10,18); M2(33,17) = M1(10,19); M2(33,18) = M1(10,20); M2(33,19) = M1(10,21); M2(33,22) = M1(10,22); M2(33,23) = M1(10,23); M2(33,24) = M1(10,24); M2(33,27) = M1(10,25); M2(33,28) = M1(10,26); M2(33,31) = M1(10,27); M2(33,37) = M1(10,28); M2(33,38) = M1(10,29); M2(33,39) = M1(10,30); M2(33,40) = M1(10,31); M2(33,41) = M1(10,32); M2(33,42) = M1(10,33); M2(33,45) = M1(10,34); M2(33,46) = M1(10,35); M2(33,47) = M1(10,36); M2(33,48) = M1(10,37); M2(33,49) = M1(10,38); M2(33,52) = M1(10,39); M2(33,53) = M1(10,40); M2(33,54) = M1(10,41); M2(33,55) = M1(10,42); M2(33,58) = M1(10,43); M2(33,59) = M1(10,44); M2(33,60) = M1(10,45); M2(33,63) = M1(10,46); M2(33,64) = M1(10,47); M2(33,67) = M1(10,48); M2(33,72) = M1(10,49); M2(33,73) = M1(10,50); M2(33,74) = M1(10,51); M2(33,75) = M1(10,52); M2(33,76) = M1(10,53); M2(33,79) = M1(10,54); M2(33,80) = M1(10,55); M2(33,81) = M1(10,56); M2(33,82) = M1(10,57); M2(33,85) = M1(10,58); M2(33,86) = M1(10,59); M2(33,87) = M1(10,60); M2(33,90) = M1(10,61); M2(33,91) = M1(10,62); M2(33,95) = M1(10,63); M2(33,101) = M1(10,64); M2(33,102) = M1(10,65); M2(33,103) = M1(10,66); M2(33,104) = M1(10,67); M2(33,107) = M1(10,68); M2(33,108) = M1(10,69); M2(33,109) = M1(10,70); M2(33,112) = M1(10,71); M2(33,113) = M1(10,72); M2(33,116) = M1(10,73); M2(33,122) = M1(10,74); M2(33,123) = M1(10,75); M2(33,124) = M1(10,76); M2(33,127) = M1(10,77); M2(33,128) = M1(10,78); M2(33,131) = M1(10,79); M2(33,137) = M1(10,80); M2(33,138) = M1(10,81); M2(33,141) = M1(10,82); M2(33,147) = M1(10,83); M2(34,7) = M1(11,11); M2(34,11) = M1(11,15); M2(34,12) = M1(11,16); M2(34,13) = M1(11,17); M2(34,16) = M1(11,18); M2(34,17) = M1(11,19); M2(34,18) = M1(11,20); M2(34,19) = M1(11,21); M2(34,22) = M1(11,22); M2(34,23) = M1(11,23); M2(34,24) = M1(11,24); M2(34,27) = M1(11,25); M2(34,28) = M1(11,26); M2(34,31) = M1(11,27); M2(34,37) = M1(11,28); M2(34,38) = M1(11,29); M2(34,39) = M1(11,30); M2(34,40) = M1(11,31); M2(34,41) = M1(11,32); M2(34,42) = M1(11,33); M2(34,45) = M1(11,34); M2(34,46) = M1(11,35); M2(34,47) = M1(11,36); M2(34,48) = M1(11,37); M2(34,49) = M1(11,38); M2(34,52) = M1(11,39); M2(34,53) = M1(11,40); M2(34,54) = M1(11,41); M2(34,55) = M1(11,42); M2(34,58) = M1(11,43); M2(34,59) = M1(11,44); M2(34,60) = M1(11,45); M2(34,63) = M1(11,46); M2(34,64) = M1(11,47); M2(34,67) = M1(11,48); M2(34,72) = M1(11,49); M2(34,73) = M1(11,50); M2(34,74) = M1(11,51); M2(34,75) = M1(11,52); M2(34,76) = M1(11,53); M2(34,79) = M1(11,54); M2(34,80) = M1(11,55); M2(34,81) = M1(11,56); M2(34,82) = M1(11,57); M2(34,85) = M1(11,58); M2(34,86) = M1(11,59); M2(34,87) = M1(11,60); M2(34,90) = M1(11,61); M2(34,91) = M1(11,62); M2(34,95) = M1(11,63); M2(34,101) = M1(11,64); M2(34,102) = M1(11,65); M2(34,103) = M1(11,66); M2(34,104) = M1(11,67); M2(34,107) = M1(11,68); M2(34,108) = M1(11,69); M2(34,109) = M1(11,70); M2(34,112) = M1(11,71); M2(34,113) = M1(11,72); M2(34,116) = M1(11,73); M2(34,122) = M1(11,74); M2(34,123) = M1(11,75); M2(34,124) = M1(11,76); M2(34,127) = M1(11,77); M2(34,128) = M1(11,78); M2(34,131) = M1(11,79); M2(34,137) = M1(11,80); M2(34,138) = M1(11,81); M2(34,141) = M1(11,82); M2(34,147) = M1(11,83); M2(35,8) = M1(12,12); M2(35,11) = M1(12,15); M2(35,12) = M1(12,16); M2(35,13) = M1(12,17); M2(35,16) = M1(12,18); M2(35,17) = M1(12,19); M2(35,18) = M1(12,20); M2(35,19) = M1(12,21); M2(35,22) = M1(12,22); M2(35,23) = M1(12,23); M2(35,24) = M1(12,24); M2(35,27) = M1(12,25); M2(35,28) = M1(12,26); M2(35,31) = M1(12,27); M2(35,37) = M1(12,28); M2(35,38) = M1(12,29); M2(35,39) = M1(12,30); M2(35,40) = M1(12,31); M2(35,41) = M1(12,32); M2(35,42) = M1(12,33); M2(35,45) = M1(12,34); M2(35,46) = M1(12,35); M2(35,47) = M1(12,36); M2(35,48) = M1(12,37); M2(35,49) = M1(12,38); M2(35,52) = M1(12,39); M2(35,53) = M1(12,40); M2(35,54) = M1(12,41); M2(35,55) = M1(12,42); M2(35,58) = M1(12,43); M2(35,59) = M1(12,44); M2(35,60) = M1(12,45); M2(35,63) = M1(12,46); M2(35,64) = M1(12,47); M2(35,67) = M1(12,48); M2(35,72) = M1(12,49); M2(35,73) = M1(12,50); M2(35,74) = M1(12,51); M2(35,75) = M1(12,52); M2(35,76) = M1(12,53); M2(35,79) = M1(12,54); M2(35,80) = M1(12,55); M2(35,81) = M1(12,56); M2(35,82) = M1(12,57); M2(35,85) = M1(12,58); M2(35,86) = M1(12,59); M2(35,87) = M1(12,60); M2(35,90) = M1(12,61); M2(35,91) = M1(12,62); M2(35,95) = M1(12,63); M2(35,101) = M1(12,64); M2(35,102) = M1(12,65); M2(35,103) = M1(12,66); M2(35,104) = M1(12,67); M2(35,107) = M1(12,68); M2(35,108) = M1(12,69); M2(35,109) = M1(12,70); M2(35,112) = M1(12,71); M2(35,113) = M1(12,72); M2(35,116) = M1(12,73); M2(35,122) = M1(12,74); M2(35,123) = M1(12,75); M2(35,124) = M1(12,76); M2(35,127) = M1(12,77); M2(35,128) = M1(12,78); M2(35,131) = M1(12,79); M2(35,137) = M1(12,80); M2(35,138) = M1(12,81); M2(35,141) = M1(12,82); M2(35,147) = M1(12,83); M2(36,10) = M1(14,14); M2(36,11) = M1(14,15); M2(36,12) = M1(14,16); M2(36,13) = M1(14,17); M2(36,16) = M1(14,18); M2(36,17) = M1(14,19); M2(36,18) = M1(14,20); M2(36,19) = M1(14,21); M2(36,22) = M1(14,22); M2(36,23) = M1(14,23); M2(36,24) = M1(14,24); M2(36,27) = M1(14,25); M2(36,28) = M1(14,26); M2(36,31) = M1(14,27); M2(36,37) = M1(14,28); M2(36,38) = M1(14,29); M2(36,39) = M1(14,30); M2(36,40) = M1(14,31); M2(36,41) = M1(14,32); M2(36,42) = M1(14,33); M2(36,45) = M1(14,34); M2(36,46) = M1(14,35); M2(36,47) = M1(14,36); M2(36,48) = M1(14,37); M2(36,49) = M1(14,38); M2(36,52) = M1(14,39); M2(36,53) = M1(14,40); M2(36,54) = M1(14,41); M2(36,55) = M1(14,42); M2(36,58) = M1(14,43); M2(36,59) = M1(14,44); M2(36,60) = M1(14,45); M2(36,63) = M1(14,46); M2(36,64) = M1(14,47); M2(36,67) = M1(14,48); M2(36,72) = M1(14,49); M2(36,73) = M1(14,50); M2(36,74) = M1(14,51); M2(36,75) = M1(14,52); M2(36,76) = M1(14,53); M2(36,79) = M1(14,54); M2(36,80) = M1(14,55); M2(36,81) = M1(14,56); M2(36,82) = M1(14,57); M2(36,85) = M1(14,58); M2(36,86) = M1(14,59); M2(36,87) = M1(14,60); M2(36,90) = M1(14,61); M2(36,91) = M1(14,62); M2(36,95) = M1(14,63); M2(36,101) = M1(14,64); M2(36,102) = M1(14,65); M2(36,103) = M1(14,66); M2(36,104) = M1(14,67); M2(36,107) = M1(14,68); M2(36,108) = M1(14,69); M2(36,109) = M1(14,70); M2(36,112) = M1(14,71); M2(36,113) = M1(14,72); M2(36,116) = M1(14,73); M2(36,122) = M1(14,74); M2(36,123) = M1(14,75); M2(36,124) = M1(14,76); M2(36,127) = M1(14,77); M2(36,128) = M1(14,78); M2(36,131) = M1(14,79); M2(36,137) = M1(14,80); M2(36,138) = M1(14,81); M2(36,141) = M1(14,82); M2(36,147) = M1(14,83); M2(37,48) = M1(3,3); M2(37,60) = M1(3,15); M2(37,61) = M1(3,16); M2(37,62) = M1(3,17); M2(37,63) = M1(3,18); M2(37,64) = M1(3,19); M2(37,65) = M1(3,20); M2(37,66) = M1(3,21); M2(37,67) = M1(3,22); M2(37,68) = M1(3,23); M2(37,69) = M1(3,24); M2(37,70) = M1(3,25); M2(37,71) = M1(3,26); M2(37,79) = M1(3,28); M2(37,80) = M1(3,29); M2(37,81) = M1(3,30); M2(37,82) = M1(3,31); M2(37,83) = M1(3,32); M2(37,84) = M1(3,33); M2(37,85) = M1(3,34); M2(37,86) = M1(3,35); M2(37,87) = M1(3,36); M2(37,88) = M1(3,37); M2(37,89) = M1(3,38); M2(37,90) = M1(3,39); M2(37,91) = M1(3,40); M2(37,92) = M1(3,41); M2(37,93) = M1(3,27); M2(37,94) = M1(3,42); M2(37,95) = M1(3,43); M2(37,96) = M1(3,44); M2(37,97) = M1(3,45); M2(37,98) = M1(3,46); M2(37,99) = M1(3,47); M2(37,100) = M1(3,48); M2(37,107) = M1(3,49); M2(37,108) = M1(3,50); M2(37,109) = M1(3,51); M2(37,110) = M1(3,52); M2(37,111) = M1(3,53); M2(37,112) = M1(3,54); M2(37,113) = M1(3,55); M2(37,114) = M1(3,56); M2(37,115) = M1(3,57); M2(37,116) = M1(3,58); M2(37,117) = M1(3,59); M2(37,118) = M1(3,60); M2(37,119) = M1(3,61); M2(37,120) = M1(3,62); M2(37,121) = M1(3,63); M2(37,127) = M1(3,64); M2(37,128) = M1(3,65); M2(37,129) = M1(3,66); M2(37,130) = M1(3,67); M2(37,131) = M1(3,68); M2(37,132) = M1(3,69); M2(37,133) = M1(3,70); M2(37,134) = M1(3,71); M2(37,135) = M1(3,72); M2(37,136) = M1(3,73); M2(37,141) = M1(3,74); M2(37,142) = M1(3,75); M2(37,143) = M1(3,76); M2(37,144) = M1(3,77); M2(37,145) = M1(3,78); M2(37,146) = M1(3,79); M2(37,150) = M1(3,80); M2(37,151) = M1(3,81); M2(37,152) = M1(3,82); M2(37,155) = M1(3,83); M2(38,49) = M1(4,4); M2(38,60) = M1(4,15); M2(38,61) = M1(4,16); M2(38,62) = M1(4,17); M2(38,63) = M1(4,18); M2(38,64) = M1(4,19); M2(38,65) = M1(4,20); M2(38,66) = M1(4,21); M2(38,67) = M1(4,22); M2(38,68) = M1(4,23); M2(38,69) = M1(4,24); M2(38,70) = M1(4,25); M2(38,71) = M1(4,26); M2(38,79) = M1(4,28); M2(38,80) = M1(4,29); M2(38,81) = M1(4,30); M2(38,82) = M1(4,31); M2(38,83) = M1(4,32); M2(38,84) = M1(4,33); M2(38,85) = M1(4,34); M2(38,86) = M1(4,35); M2(38,87) = M1(4,36); M2(38,88) = M1(4,37); M2(38,89) = M1(4,38); M2(38,90) = M1(4,39); M2(38,91) = M1(4,40); M2(38,92) = M1(4,41); M2(38,93) = M1(4,27); M2(38,94) = M1(4,42); M2(38,95) = M1(4,43); M2(38,96) = M1(4,44); M2(38,97) = M1(4,45); M2(38,98) = M1(4,46); M2(38,99) = M1(4,47); M2(38,100) = M1(4,48); M2(38,107) = M1(4,49); M2(38,108) = M1(4,50); M2(38,109) = M1(4,51); M2(38,110) = M1(4,52); M2(38,111) = M1(4,53); M2(38,112) = M1(4,54); M2(38,113) = M1(4,55); M2(38,114) = M1(4,56); M2(38,115) = M1(4,57); M2(38,116) = M1(4,58); M2(38,117) = M1(4,59); M2(38,118) = M1(4,60); M2(38,119) = M1(4,61); M2(38,120) = M1(4,62); M2(38,121) = M1(4,63); M2(38,127) = M1(4,64); M2(38,128) = M1(4,65); M2(38,129) = M1(4,66); M2(38,130) = M1(4,67); M2(38,131) = M1(4,68); M2(38,132) = M1(4,69); M2(38,133) = M1(4,70); M2(38,134) = M1(4,71); M2(38,135) = M1(4,72); M2(38,136) = M1(4,73); M2(38,141) = M1(4,74); M2(38,142) = M1(4,75); M2(38,143) = M1(4,76); M2(38,144) = M1(4,77); M2(38,145) = M1(4,78); M2(38,146) = M1(4,79); M2(38,150) = M1(4,80); M2(38,151) = M1(4,81); M2(38,152) = M1(4,82); M2(38,155) = M1(4,83); M2(39,50) = M1(5,5); M2(39,60) = M1(5,15); M2(39,61) = M1(5,16); M2(39,62) = M1(5,17); M2(39,63) = M1(5,18); M2(39,64) = M1(5,19); M2(39,65) = M1(5,20); M2(39,66) = M1(5,21); M2(39,67) = M1(5,22); M2(39,68) = M1(5,23); M2(39,69) = M1(5,24); M2(39,70) = M1(5,25); M2(39,71) = M1(5,26); M2(39,79) = M1(5,28); M2(39,80) = M1(5,29); M2(39,81) = M1(5,30); M2(39,82) = M1(5,31); M2(39,83) = M1(5,32); M2(39,84) = M1(5,33); M2(39,85) = M1(5,34); M2(39,86) = M1(5,35); M2(39,87) = M1(5,36); M2(39,88) = M1(5,37); M2(39,89) = M1(5,38); M2(39,90) = M1(5,39); M2(39,91) = M1(5,40); M2(39,92) = M1(5,41); M2(39,93) = M1(5,27); M2(39,94) = M1(5,42); M2(39,95) = M1(5,43); M2(39,96) = M1(5,44); M2(39,97) = M1(5,45); M2(39,98) = M1(5,46); M2(39,99) = M1(5,47); M2(39,100) = M1(5,48); M2(39,107) = M1(5,49); M2(39,108) = M1(5,50); M2(39,109) = M1(5,51); M2(39,110) = M1(5,52); M2(39,111) = M1(5,53); M2(39,112) = M1(5,54); M2(39,113) = M1(5,55); M2(39,114) = M1(5,56); M2(39,115) = M1(5,57); M2(39,116) = M1(5,58); M2(39,117) = M1(5,59); M2(39,118) = M1(5,60); M2(39,119) = M1(5,61); M2(39,120) = M1(5,62); M2(39,121) = M1(5,63); M2(39,127) = M1(5,64); M2(39,128) = M1(5,65); M2(39,129) = M1(5,66); M2(39,130) = M1(5,67); M2(39,131) = M1(5,68); M2(39,132) = M1(5,69); M2(39,133) = M1(5,70); M2(39,134) = M1(5,71); M2(39,135) = M1(5,72); M2(39,136) = M1(5,73); M2(39,141) = M1(5,74); M2(39,142) = M1(5,75); M2(39,143) = M1(5,76); M2(39,144) = M1(5,77); M2(39,145) = M1(5,78); M2(39,146) = M1(5,79); M2(39,150) = M1(5,80); M2(39,151) = M1(5,81); M2(39,152) = M1(5,82); M2(39,155) = M1(5,83); M2(40,51) = M1(6,6); M2(40,60) = M1(6,15); M2(40,61) = M1(6,16); M2(40,62) = M1(6,17); M2(40,63) = M1(6,18); M2(40,64) = M1(6,19); M2(40,65) = M1(6,20); M2(40,66) = M1(6,21); M2(40,67) = M1(6,22); M2(40,68) = M1(6,23); M2(40,69) = M1(6,24); M2(40,70) = M1(6,25); M2(40,71) = M1(6,26); M2(40,79) = M1(6,28); M2(40,80) = M1(6,29); M2(40,81) = M1(6,30); M2(40,82) = M1(6,31); M2(40,83) = M1(6,32); M2(40,84) = M1(6,33); M2(40,85) = M1(6,34); M2(40,86) = M1(6,35); M2(40,87) = M1(6,36); M2(40,88) = M1(6,37); M2(40,89) = M1(6,38); M2(40,90) = M1(6,39); M2(40,91) = M1(6,40); M2(40,92) = M1(6,41); M2(40,93) = M1(6,27); M2(40,94) = M1(6,42); M2(40,95) = M1(6,43); M2(40,96) = M1(6,44); M2(40,97) = M1(6,45); M2(40,98) = M1(6,46); M2(40,99) = M1(6,47); M2(40,100) = M1(6,48); M2(40,107) = M1(6,49); M2(40,108) = M1(6,50); M2(40,109) = M1(6,51); M2(40,110) = M1(6,52); M2(40,111) = M1(6,53); M2(40,112) = M1(6,54); M2(40,113) = M1(6,55); M2(40,114) = M1(6,56); M2(40,115) = M1(6,57); M2(40,116) = M1(6,58); M2(40,117) = M1(6,59); M2(40,118) = M1(6,60); M2(40,119) = M1(6,61); M2(40,120) = M1(6,62); M2(40,121) = M1(6,63); M2(40,127) = M1(6,64); M2(40,128) = M1(6,65); M2(40,129) = M1(6,66); M2(40,130) = M1(6,67); M2(40,131) = M1(6,68); M2(40,132) = M1(6,69); M2(40,133) = M1(6,70); M2(40,134) = M1(6,71); M2(40,135) = M1(6,72); M2(40,136) = M1(6,73); M2(40,141) = M1(6,74); M2(40,142) = M1(6,75); M2(40,143) = M1(6,76); M2(40,144) = M1(6,77); M2(40,145) = M1(6,78); M2(40,146) = M1(6,79); M2(40,150) = M1(6,80); M2(40,151) = M1(6,81); M2(40,152) = M1(6,82); M2(40,155) = M1(6,83); M2(41,52) = M1(7,7); M2(41,60) = M1(7,15); M2(41,61) = M1(7,16); M2(41,62) = M1(7,17); M2(41,63) = M1(7,18); M2(41,64) = M1(7,19); M2(41,65) = M1(7,20); M2(41,66) = M1(7,21); M2(41,67) = M1(7,22); M2(41,68) = M1(7,23); M2(41,69) = M1(7,24); M2(41,70) = M1(7,25); M2(41,71) = M1(7,26); M2(41,79) = M1(7,28); M2(41,80) = M1(7,29); M2(41,81) = M1(7,30); M2(41,82) = M1(7,31); M2(41,83) = M1(7,32); M2(41,84) = M1(7,33); M2(41,85) = M1(7,34); M2(41,86) = M1(7,35); M2(41,87) = M1(7,36); M2(41,88) = M1(7,37); M2(41,89) = M1(7,38); M2(41,90) = M1(7,39); M2(41,91) = M1(7,40); M2(41,92) = M1(7,41); M2(41,93) = M1(7,27); M2(41,94) = M1(7,42); M2(41,95) = M1(7,43); M2(41,96) = M1(7,44); M2(41,97) = M1(7,45); M2(41,98) = M1(7,46); M2(41,99) = M1(7,47); M2(41,100) = M1(7,48); M2(41,107) = M1(7,49); M2(41,108) = M1(7,50); M2(41,109) = M1(7,51); M2(41,110) = M1(7,52); M2(41,111) = M1(7,53); M2(41,112) = M1(7,54); M2(41,113) = M1(7,55); M2(41,114) = M1(7,56); M2(41,115) = M1(7,57); M2(41,116) = M1(7,58); M2(41,117) = M1(7,59); M2(41,118) = M1(7,60); M2(41,119) = M1(7,61); M2(41,120) = M1(7,62); M2(41,121) = M1(7,63); M2(41,127) = M1(7,64); M2(41,128) = M1(7,65); M2(41,129) = M1(7,66); M2(41,130) = M1(7,67); M2(41,131) = M1(7,68); M2(41,132) = M1(7,69); M2(41,133) = M1(7,70); M2(41,134) = M1(7,71); M2(41,135) = M1(7,72); M2(41,136) = M1(7,73); M2(41,141) = M1(7,74); M2(41,142) = M1(7,75); M2(41,143) = M1(7,76); M2(41,144) = M1(7,77); M2(41,145) = M1(7,78); M2(41,146) = M1(7,79); M2(41,150) = M1(7,80); M2(41,151) = M1(7,81); M2(41,152) = M1(7,82); M2(41,155) = M1(7,83); M2(42,53) = M1(8,8); M2(42,60) = M1(8,15); M2(42,61) = M1(8,16); M2(42,62) = M1(8,17); M2(42,63) = M1(8,18); M2(42,64) = M1(8,19); M2(42,65) = M1(8,20); M2(42,66) = M1(8,21); M2(42,67) = M1(8,22); M2(42,68) = M1(8,23); M2(42,69) = M1(8,24); M2(42,70) = M1(8,25); M2(42,71) = M1(8,26); M2(42,79) = M1(8,28); M2(42,80) = M1(8,29); M2(42,81) = M1(8,30); M2(42,82) = M1(8,31); M2(42,83) = M1(8,32); M2(42,84) = M1(8,33); M2(42,85) = M1(8,34); M2(42,86) = M1(8,35); M2(42,87) = M1(8,36); M2(42,88) = M1(8,37); M2(42,89) = M1(8,38); M2(42,90) = M1(8,39); M2(42,91) = M1(8,40); M2(42,92) = M1(8,41); M2(42,93) = M1(8,27); M2(42,94) = M1(8,42); M2(42,95) = M1(8,43); M2(42,96) = M1(8,44); M2(42,97) = M1(8,45); M2(42,98) = M1(8,46); M2(42,99) = M1(8,47); M2(42,100) = M1(8,48); M2(42,107) = M1(8,49); M2(42,108) = M1(8,50); M2(42,109) = M1(8,51); M2(42,110) = M1(8,52); M2(42,111) = M1(8,53); M2(42,112) = M1(8,54); M2(42,113) = M1(8,55); M2(42,114) = M1(8,56); M2(42,115) = M1(8,57); M2(42,116) = M1(8,58); M2(42,117) = M1(8,59); M2(42,118) = M1(8,60); M2(42,119) = M1(8,61); M2(42,120) = M1(8,62); M2(42,121) = M1(8,63); M2(42,127) = M1(8,64); M2(42,128) = M1(8,65); M2(42,129) = M1(8,66); M2(42,130) = M1(8,67); M2(42,131) = M1(8,68); M2(42,132) = M1(8,69); M2(42,133) = M1(8,70); M2(42,134) = M1(8,71); M2(42,135) = M1(8,72); M2(42,136) = M1(8,73); M2(42,141) = M1(8,74); M2(42,142) = M1(8,75); M2(42,143) = M1(8,76); M2(42,144) = M1(8,77); M2(42,145) = M1(8,78); M2(42,146) = M1(8,79); M2(42,150) = M1(8,80); M2(42,151) = M1(8,81); M2(42,152) = M1(8,82); M2(42,155) = M1(8,83); M2(43,54) = M1(9,9); M2(43,60) = M1(9,15); M2(43,61) = M1(9,16); M2(43,62) = M1(9,17); M2(43,63) = M1(9,18); M2(43,64) = M1(9,19); M2(43,65) = M1(9,20); M2(43,66) = M1(9,21); M2(43,67) = M1(9,22); M2(43,68) = M1(9,23); M2(43,69) = M1(9,24); M2(43,70) = M1(9,25); M2(43,71) = M1(9,26); M2(43,79) = M1(9,28); M2(43,80) = M1(9,29); M2(43,81) = M1(9,30); M2(43,82) = M1(9,31); M2(43,83) = M1(9,32); M2(43,84) = M1(9,33); M2(43,85) = M1(9,34); M2(43,86) = M1(9,35); M2(43,87) = M1(9,36); M2(43,88) = M1(9,37); M2(43,89) = M1(9,38); M2(43,90) = M1(9,39); M2(43,91) = M1(9,40); M2(43,92) = M1(9,41); M2(43,93) = M1(9,27); M2(43,94) = M1(9,42); M2(43,95) = M1(9,43); M2(43,96) = M1(9,44); M2(43,97) = M1(9,45); M2(43,98) = M1(9,46); M2(43,99) = M1(9,47); M2(43,100) = M1(9,48); M2(43,107) = M1(9,49); M2(43,108) = M1(9,50); M2(43,109) = M1(9,51); M2(43,110) = M1(9,52); M2(43,111) = M1(9,53); M2(43,112) = M1(9,54); M2(43,113) = M1(9,55); M2(43,114) = M1(9,56); M2(43,115) = M1(9,57); M2(43,116) = M1(9,58); M2(43,117) = M1(9,59); M2(43,118) = M1(9,60); M2(43,119) = M1(9,61); M2(43,120) = M1(9,62); M2(43,121) = M1(9,63); M2(43,127) = M1(9,64); M2(43,128) = M1(9,65); M2(43,129) = M1(9,66); M2(43,130) = M1(9,67); M2(43,131) = M1(9,68); M2(43,132) = M1(9,69); M2(43,133) = M1(9,70); M2(43,134) = M1(9,71); M2(43,135) = M1(9,72); M2(43,136) = M1(9,73); M2(43,141) = M1(9,74); M2(43,142) = M1(9,75); M2(43,143) = M1(9,76); M2(43,144) = M1(9,77); M2(43,145) = M1(9,78); M2(43,146) = M1(9,79); M2(43,150) = M1(9,80); M2(43,151) = M1(9,81); M2(43,152) = M1(9,82); M2(43,155) = M1(9,83); M2(44,55) = M1(10,10); M2(44,60) = M1(10,15); M2(44,61) = M1(10,16); M2(44,62) = M1(10,17); M2(44,63) = M1(10,18); M2(44,64) = M1(10,19); M2(44,65) = M1(10,20); M2(44,66) = M1(10,21); M2(44,67) = M1(10,22); M2(44,68) = M1(10,23); M2(44,69) = M1(10,24); M2(44,70) = M1(10,25); M2(44,71) = M1(10,26); M2(44,79) = M1(10,28); M2(44,80) = M1(10,29); M2(44,81) = M1(10,30); M2(44,82) = M1(10,31); M2(44,83) = M1(10,32); M2(44,84) = M1(10,33); M2(44,85) = M1(10,34); M2(44,86) = M1(10,35); M2(44,87) = M1(10,36); M2(44,88) = M1(10,37); M2(44,89) = M1(10,38); M2(44,90) = M1(10,39); M2(44,91) = M1(10,40); M2(44,92) = M1(10,41); M2(44,93) = M1(10,27); M2(44,94) = M1(10,42); M2(44,95) = M1(10,43); M2(44,96) = M1(10,44); M2(44,97) = M1(10,45); M2(44,98) = M1(10,46); M2(44,99) = M1(10,47); M2(44,100) = M1(10,48); M2(44,107) = M1(10,49); M2(44,108) = M1(10,50); M2(44,109) = M1(10,51); M2(44,110) = M1(10,52); M2(44,111) = M1(10,53); M2(44,112) = M1(10,54); M2(44,113) = M1(10,55); M2(44,114) = M1(10,56); M2(44,115) = M1(10,57); M2(44,116) = M1(10,58); M2(44,117) = M1(10,59); M2(44,118) = M1(10,60); M2(44,119) = M1(10,61); M2(44,120) = M1(10,62); M2(44,121) = M1(10,63); M2(44,127) = M1(10,64); M2(44,128) = M1(10,65); M2(44,129) = M1(10,66); M2(44,130) = M1(10,67); M2(44,131) = M1(10,68); M2(44,132) = M1(10,69); M2(44,133) = M1(10,70); M2(44,134) = M1(10,71); M2(44,135) = M1(10,72); M2(44,136) = M1(10,73); M2(44,141) = M1(10,74); M2(44,142) = M1(10,75); M2(44,143) = M1(10,76); M2(44,144) = M1(10,77); M2(44,145) = M1(10,78); M2(44,146) = M1(10,79); M2(44,150) = M1(10,80); M2(44,151) = M1(10,81); M2(44,152) = M1(10,82); M2(44,155) = M1(10,83); M2(45,56) = M1(11,11); M2(45,60) = M1(11,15); M2(45,61) = M1(11,16); M2(45,62) = M1(11,17); M2(45,63) = M1(11,18); M2(45,64) = M1(11,19); M2(45,65) = M1(11,20); M2(45,66) = M1(11,21); M2(45,67) = M1(11,22); M2(45,68) = M1(11,23); M2(45,69) = M1(11,24); M2(45,70) = M1(11,25); M2(45,71) = M1(11,26); M2(45,79) = M1(11,28); M2(45,80) = M1(11,29); M2(45,81) = M1(11,30); M2(45,82) = M1(11,31); M2(45,83) = M1(11,32); M2(45,84) = M1(11,33); M2(45,85) = M1(11,34); M2(45,86) = M1(11,35); M2(45,87) = M1(11,36); M2(45,88) = M1(11,37); M2(45,89) = M1(11,38); M2(45,90) = M1(11,39); M2(45,91) = M1(11,40); M2(45,92) = M1(11,41); M2(45,93) = M1(11,27); M2(45,94) = M1(11,42); M2(45,95) = M1(11,43); M2(45,96) = M1(11,44); M2(45,97) = M1(11,45); M2(45,98) = M1(11,46); M2(45,99) = M1(11,47); M2(45,100) = M1(11,48); M2(45,107) = M1(11,49); M2(45,108) = M1(11,50); M2(45,109) = M1(11,51); M2(45,110) = M1(11,52); M2(45,111) = M1(11,53); M2(45,112) = M1(11,54); M2(45,113) = M1(11,55); M2(45,114) = M1(11,56); M2(45,115) = M1(11,57); M2(45,116) = M1(11,58); M2(45,117) = M1(11,59); M2(45,118) = M1(11,60); M2(45,119) = M1(11,61); M2(45,120) = M1(11,62); M2(45,121) = M1(11,63); M2(45,127) = M1(11,64); M2(45,128) = M1(11,65); M2(45,129) = M1(11,66); M2(45,130) = M1(11,67); M2(45,131) = M1(11,68); M2(45,132) = M1(11,69); M2(45,133) = M1(11,70); M2(45,134) = M1(11,71); M2(45,135) = M1(11,72); M2(45,136) = M1(11,73); M2(45,141) = M1(11,74); M2(45,142) = M1(11,75); M2(45,143) = M1(11,76); M2(45,144) = M1(11,77); M2(45,145) = M1(11,78); M2(45,146) = M1(11,79); M2(45,150) = M1(11,80); M2(45,151) = M1(11,81); M2(45,152) = M1(11,82); M2(45,155) = M1(11,83); M2(46,57) = M1(12,12); M2(46,60) = M1(12,15); M2(46,61) = M1(12,16); M2(46,62) = M1(12,17); M2(46,63) = M1(12,18); M2(46,64) = M1(12,19); M2(46,65) = M1(12,20); M2(46,66) = M1(12,21); M2(46,67) = M1(12,22); M2(46,68) = M1(12,23); M2(46,69) = M1(12,24); M2(46,70) = M1(12,25); M2(46,71) = M1(12,26); M2(46,79) = M1(12,28); M2(46,80) = M1(12,29); M2(46,81) = M1(12,30); M2(46,82) = M1(12,31); M2(46,83) = M1(12,32); M2(46,84) = M1(12,33); M2(46,85) = M1(12,34); M2(46,86) = M1(12,35); M2(46,87) = M1(12,36); M2(46,88) = M1(12,37); M2(46,89) = M1(12,38); M2(46,90) = M1(12,39); M2(46,91) = M1(12,40); M2(46,92) = M1(12,41); M2(46,93) = M1(12,27); M2(46,94) = M1(12,42); M2(46,95) = M1(12,43); M2(46,96) = M1(12,44); M2(46,97) = M1(12,45); M2(46,98) = M1(12,46); M2(46,99) = M1(12,47); M2(46,100) = M1(12,48); M2(46,107) = M1(12,49); M2(46,108) = M1(12,50); M2(46,109) = M1(12,51); M2(46,110) = M1(12,52); M2(46,111) = M1(12,53); M2(46,112) = M1(12,54); M2(46,113) = M1(12,55); M2(46,114) = M1(12,56); M2(46,115) = M1(12,57); M2(46,116) = M1(12,58); M2(46,117) = M1(12,59); M2(46,118) = M1(12,60); M2(46,119) = M1(12,61); M2(46,120) = M1(12,62); M2(46,121) = M1(12,63); M2(46,127) = M1(12,64); M2(46,128) = M1(12,65); M2(46,129) = M1(12,66); M2(46,130) = M1(12,67); M2(46,131) = M1(12,68); M2(46,132) = M1(12,69); M2(46,133) = M1(12,70); M2(46,134) = M1(12,71); M2(46,135) = M1(12,72); M2(46,136) = M1(12,73); M2(46,141) = M1(12,74); M2(46,142) = M1(12,75); M2(46,143) = M1(12,76); M2(46,144) = M1(12,77); M2(46,145) = M1(12,78); M2(46,146) = M1(12,79); M2(46,150) = M1(12,80); M2(46,151) = M1(12,81); M2(46,152) = M1(12,82); M2(46,155) = M1(12,83); M2(47,58) = M1(13,13); M2(47,60) = M1(13,15); M2(47,61) = M1(13,16); M2(47,62) = M1(13,17); M2(47,63) = M1(13,18); M2(47,64) = M1(13,19); M2(47,65) = M1(13,20); M2(47,66) = M1(13,21); M2(47,67) = M1(13,22); M2(47,68) = M1(13,23); M2(47,69) = M1(13,24); M2(47,70) = M1(13,25); M2(47,71) = M1(13,26); M2(47,79) = M1(13,28); M2(47,80) = M1(13,29); M2(47,81) = M1(13,30); M2(47,82) = M1(13,31); M2(47,83) = M1(13,32); M2(47,84) = M1(13,33); M2(47,85) = M1(13,34); M2(47,86) = M1(13,35); M2(47,87) = M1(13,36); M2(47,88) = M1(13,37); M2(47,89) = M1(13,38); M2(47,90) = M1(13,39); M2(47,91) = M1(13,40); M2(47,92) = M1(13,41); M2(47,93) = M1(13,27); M2(47,94) = M1(13,42); M2(47,95) = M1(13,43); M2(47,96) = M1(13,44); M2(47,97) = M1(13,45); M2(47,98) = M1(13,46); M2(47,99) = M1(13,47); M2(47,100) = M1(13,48); M2(47,107) = M1(13,49); M2(47,108) = M1(13,50); M2(47,109) = M1(13,51); M2(47,110) = M1(13,52); M2(47,111) = M1(13,53); M2(47,112) = M1(13,54); M2(47,113) = M1(13,55); M2(47,114) = M1(13,56); M2(47,115) = M1(13,57); M2(47,116) = M1(13,58); M2(47,117) = M1(13,59); M2(47,118) = M1(13,60); M2(47,119) = M1(13,61); M2(47,120) = M1(13,62); M2(47,121) = M1(13,63); M2(47,127) = M1(13,64); M2(47,128) = M1(13,65); M2(47,129) = M1(13,66); M2(47,130) = M1(13,67); M2(47,131) = M1(13,68); M2(47,132) = M1(13,69); M2(47,133) = M1(13,70); M2(47,134) = M1(13,71); M2(47,135) = M1(13,72); M2(47,136) = M1(13,73); M2(47,141) = M1(13,74); M2(47,142) = M1(13,75); M2(47,143) = M1(13,76); M2(47,144) = M1(13,77); M2(47,145) = M1(13,78); M2(47,146) = M1(13,79); M2(47,150) = M1(13,80); M2(47,151) = M1(13,81); M2(47,152) = M1(13,82); M2(47,155) = M1(13,83); M2(48,59) = M1(14,14); M2(48,60) = M1(14,15); M2(48,61) = M1(14,16); M2(48,62) = M1(14,17); M2(48,63) = M1(14,18); M2(48,64) = M1(14,19); M2(48,65) = M1(14,20); M2(48,66) = M1(14,21); M2(48,67) = M1(14,22); M2(48,68) = M1(14,23); M2(48,69) = M1(14,24); M2(48,70) = M1(14,25); M2(48,71) = M1(14,26); M2(48,79) = M1(14,28); M2(48,80) = M1(14,29); M2(48,81) = M1(14,30); M2(48,82) = M1(14,31); M2(48,83) = M1(14,32); M2(48,84) = M1(14,33); M2(48,85) = M1(14,34); M2(48,86) = M1(14,35); M2(48,87) = M1(14,36); M2(48,88) = M1(14,37); M2(48,89) = M1(14,38); M2(48,90) = M1(14,39); M2(48,91) = M1(14,40); M2(48,92) = M1(14,41); M2(48,93) = M1(14,27); M2(48,94) = M1(14,42); M2(48,95) = M1(14,43); M2(48,96) = M1(14,44); M2(48,97) = M1(14,45); M2(48,98) = M1(14,46); M2(48,99) = M1(14,47); M2(48,100) = M1(14,48); M2(48,107) = M1(14,49); M2(48,108) = M1(14,50); M2(48,109) = M1(14,51); M2(48,110) = M1(14,52); M2(48,111) = M1(14,53); M2(48,112) = M1(14,54); M2(48,113) = M1(14,55); M2(48,114) = M1(14,56); M2(48,115) = M1(14,57); M2(48,116) = M1(14,58); M2(48,117) = M1(14,59); M2(48,118) = M1(14,60); M2(48,119) = M1(14,61); M2(48,120) = M1(14,62); M2(48,121) = M1(14,63); M2(48,127) = M1(14,64); M2(48,128) = M1(14,65); M2(48,129) = M1(14,66); M2(48,130) = M1(14,67); M2(48,131) = M1(14,68); M2(48,132) = M1(14,69); M2(48,133) = M1(14,70); M2(48,134) = M1(14,71); M2(48,135) = M1(14,72); M2(48,136) = M1(14,73); M2(48,141) = M1(14,74); M2(48,142) = M1(14,75); M2(48,143) = M1(14,76); M2(48,144) = M1(14,77); M2(48,145) = M1(14,78); M2(48,146) = M1(14,79); M2(48,150) = M1(14,80); M2(48,151) = M1(14,81); M2(48,152) = M1(14,82); M2(48,155) = M1(14,83); M2(49,39) = M1(1,1); M2(49,55) = M1(1,15); M2(49,56) = M1(1,16); M2(49,57) = M1(1,17); M2(49,59) = M1(1,18); M2(49,60) = M1(1,19); M2(49,61) = M1(1,20); M2(49,62) = M1(1,21); M2(49,64) = M1(1,22); M2(49,65) = M1(1,23); M2(49,66) = M1(1,24); M2(49,68) = M1(1,25); M2(49,69) = M1(1,26); M2(49,71) = M1(1,27); M2(49,73) = M1(1,28); M2(49,74) = M1(1,29); M2(49,75) = M1(1,30); M2(49,76) = M1(1,31); M2(49,77) = M1(1,32); M2(49,78) = M1(1,33); M2(49,80) = M1(1,34); M2(49,81) = M1(1,35); M2(49,82) = M1(1,36); M2(49,83) = M1(1,37); M2(49,84) = M1(1,38); M2(49,86) = M1(1,39); M2(49,87) = M1(1,40); M2(49,88) = M1(1,41); M2(49,89) = M1(1,42); M2(49,91) = M1(1,43); M2(49,92) = M1(1,44); M2(49,94) = M1(1,45); M2(49,96) = M1(1,46); M2(49,97) = M1(1,47); M2(49,99) = M1(1,48); M2(49,102) = M1(1,49); M2(49,103) = M1(1,50); M2(49,104) = M1(1,51); M2(49,105) = M1(1,52); M2(49,106) = M1(1,53); M2(49,108) = M1(1,54); M2(49,109) = M1(1,55); M2(49,110) = M1(1,56); M2(49,111) = M1(1,57); M2(49,113) = M1(1,58); M2(49,114) = M1(1,59); M2(49,115) = M1(1,60); M2(49,117) = M1(1,61); M2(49,118) = M1(1,62); M2(49,120) = M1(1,63); M2(49,123) = M1(1,64); M2(49,124) = M1(1,65); M2(49,125) = M1(1,66); M2(49,126) = M1(1,67); M2(49,128) = M1(1,68); M2(49,129) = M1(1,69); M2(49,130) = M1(1,70); M2(49,132) = M1(1,71); M2(49,133) = M1(1,72); M2(49,135) = M1(1,73); M2(49,138) = M1(1,74); M2(49,139) = M1(1,75); M2(49,140) = M1(1,76); M2(49,142) = M1(1,77); M2(49,143) = M1(1,78); M2(49,145) = M1(1,79); M2(49,148) = M1(1,80); M2(49,149) = M1(1,81); M2(49,151) = M1(1,82); M2(49,154) = M1(1,83); M2(50,40) = M1(2,2); M2(50,55) = M1(2,15); M2(50,56) = M1(2,16); M2(50,57) = M1(2,17); M2(50,59) = M1(2,18); M2(50,60) = M1(2,19); M2(50,61) = M1(2,20); M2(50,62) = M1(2,21); M2(50,64) = M1(2,22); M2(50,65) = M1(2,23); M2(50,66) = M1(2,24); M2(50,68) = M1(2,25); M2(50,69) = M1(2,26); M2(50,71) = M1(2,27); M2(50,73) = M1(2,28); M2(50,74) = M1(2,29); M2(50,75) = M1(2,30); M2(50,76) = M1(2,31); M2(50,77) = M1(2,32); M2(50,78) = M1(2,33); M2(50,80) = M1(2,34); M2(50,81) = M1(2,35); M2(50,82) = M1(2,36); M2(50,83) = M1(2,37); M2(50,84) = M1(2,38); M2(50,86) = M1(2,39); M2(50,87) = M1(2,40); M2(50,88) = M1(2,41); M2(50,89) = M1(2,42); M2(50,91) = M1(2,43); M2(50,92) = M1(2,44); M2(50,94) = M1(2,45); M2(50,96) = M1(2,46); M2(50,97) = M1(2,47); M2(50,99) = M1(2,48); M2(50,102) = M1(2,49); M2(50,103) = M1(2,50); M2(50,104) = M1(2,51); M2(50,105) = M1(2,52); M2(50,106) = M1(2,53); M2(50,108) = M1(2,54); M2(50,109) = M1(2,55); M2(50,110) = M1(2,56); M2(50,111) = M1(2,57); M2(50,113) = M1(2,58); M2(50,114) = M1(2,59); M2(50,115) = M1(2,60); M2(50,117) = M1(2,61); M2(50,118) = M1(2,62); M2(50,120) = M1(2,63); M2(50,123) = M1(2,64); M2(50,124) = M1(2,65); M2(50,125) = M1(2,66); M2(50,126) = M1(2,67); M2(50,128) = M1(2,68); M2(50,129) = M1(2,69); M2(50,130) = M1(2,70); M2(50,132) = M1(2,71); M2(50,133) = M1(2,72); M2(50,135) = M1(2,73); M2(50,138) = M1(2,74); M2(50,139) = M1(2,75); M2(50,140) = M1(2,76); M2(50,142) = M1(2,77); M2(50,143) = M1(2,78); M2(50,145) = M1(2,79); M2(50,148) = M1(2,80); M2(50,149) = M1(2,81); M2(50,151) = M1(2,82); M2(50,154) = M1(2,83); M2(51,41) = M1(3,3); M2(51,55) = M1(3,15); M2(51,56) = M1(3,16); M2(51,57) = M1(3,17); M2(51,59) = M1(3,18); M2(51,60) = M1(3,19); M2(51,61) = M1(3,20); M2(51,62) = M1(3,21); M2(51,64) = M1(3,22); M2(51,65) = M1(3,23); M2(51,66) = M1(3,24); M2(51,68) = M1(3,25); M2(51,69) = M1(3,26); M2(51,71) = M1(3,27); M2(51,73) = M1(3,28); M2(51,74) = M1(3,29); M2(51,75) = M1(3,30); M2(51,76) = M1(3,31); M2(51,77) = M1(3,32); M2(51,78) = M1(3,33); M2(51,80) = M1(3,34); M2(51,81) = M1(3,35); M2(51,82) = M1(3,36); M2(51,83) = M1(3,37); M2(51,84) = M1(3,38); M2(51,86) = M1(3,39); M2(51,87) = M1(3,40); M2(51,88) = M1(3,41); M2(51,89) = M1(3,42); M2(51,91) = M1(3,43); M2(51,92) = M1(3,44); M2(51,94) = M1(3,45); M2(51,96) = M1(3,46); M2(51,97) = M1(3,47); M2(51,99) = M1(3,48); M2(51,102) = M1(3,49); M2(51,103) = M1(3,50); M2(51,104) = M1(3,51); M2(51,105) = M1(3,52); M2(51,106) = M1(3,53); M2(51,108) = M1(3,54); M2(51,109) = M1(3,55); M2(51,110) = M1(3,56); M2(51,111) = M1(3,57); M2(51,113) = M1(3,58); M2(51,114) = M1(3,59); M2(51,115) = M1(3,60); M2(51,117) = M1(3,61); M2(51,118) = M1(3,62); M2(51,120) = M1(3,63); M2(51,123) = M1(3,64); M2(51,124) = M1(3,65); M2(51,125) = M1(3,66); M2(51,126) = M1(3,67); M2(51,128) = M1(3,68); M2(51,129) = M1(3,69); M2(51,130) = M1(3,70); M2(51,132) = M1(3,71); M2(51,133) = M1(3,72); M2(51,135) = M1(3,73); M2(51,138) = M1(3,74); M2(51,139) = M1(3,75); M2(51,140) = M1(3,76); M2(51,142) = M1(3,77); M2(51,143) = M1(3,78); M2(51,145) = M1(3,79); M2(51,148) = M1(3,80); M2(51,149) = M1(3,81); M2(51,151) = M1(3,82); M2(51,154) = M1(3,83); M2(52,42) = M1(4,4); M2(52,55) = M1(4,15); M2(52,56) = M1(4,16); M2(52,57) = M1(4,17); M2(52,59) = M1(4,18); M2(52,60) = M1(4,19); M2(52,61) = M1(4,20); M2(52,62) = M1(4,21); M2(52,64) = M1(4,22); M2(52,65) = M1(4,23); M2(52,66) = M1(4,24); M2(52,68) = M1(4,25); M2(52,69) = M1(4,26); M2(52,71) = M1(4,27); M2(52,73) = M1(4,28); M2(52,74) = M1(4,29); M2(52,75) = M1(4,30); M2(52,76) = M1(4,31); M2(52,77) = M1(4,32); M2(52,78) = M1(4,33); M2(52,80) = M1(4,34); M2(52,81) = M1(4,35); M2(52,82) = M1(4,36); M2(52,83) = M1(4,37); M2(52,84) = M1(4,38); M2(52,86) = M1(4,39); M2(52,87) = M1(4,40); M2(52,88) = M1(4,41); M2(52,89) = M1(4,42); M2(52,91) = M1(4,43); M2(52,92) = M1(4,44); M2(52,94) = M1(4,45); M2(52,96) = M1(4,46); M2(52,97) = M1(4,47); M2(52,99) = M1(4,48); M2(52,102) = M1(4,49); M2(52,103) = M1(4,50); M2(52,104) = M1(4,51); M2(52,105) = M1(4,52); M2(52,106) = M1(4,53); M2(52,108) = M1(4,54); M2(52,109) = M1(4,55); M2(52,110) = M1(4,56); M2(52,111) = M1(4,57); M2(52,113) = M1(4,58); M2(52,114) = M1(4,59); M2(52,115) = M1(4,60); M2(52,117) = M1(4,61); M2(52,118) = M1(4,62); M2(52,120) = M1(4,63); M2(52,123) = M1(4,64); M2(52,124) = M1(4,65); M2(52,125) = M1(4,66); M2(52,126) = M1(4,67); M2(52,128) = M1(4,68); M2(52,129) = M1(4,69); M2(52,130) = M1(4,70); M2(52,132) = M1(4,71); M2(52,133) = M1(4,72); M2(52,135) = M1(4,73); M2(52,138) = M1(4,74); M2(52,139) = M1(4,75); M2(52,140) = M1(4,76); M2(52,142) = M1(4,77); M2(52,143) = M1(4,78); M2(52,145) = M1(4,79); M2(52,148) = M1(4,80); M2(52,149) = M1(4,81); M2(52,151) = M1(4,82); M2(52,154) = M1(4,83); M2(53,43) = M1(5,5); M2(53,55) = M1(5,15); M2(53,56) = M1(5,16); M2(53,57) = M1(5,17); M2(53,59) = M1(5,18); M2(53,60) = M1(5,19); M2(53,61) = M1(5,20); M2(53,62) = M1(5,21); M2(53,64) = M1(5,22); M2(53,65) = M1(5,23); M2(53,66) = M1(5,24); M2(53,68) = M1(5,25); M2(53,69) = M1(5,26); M2(53,71) = M1(5,27); M2(53,73) = M1(5,28); M2(53,74) = M1(5,29); M2(53,75) = M1(5,30); M2(53,76) = M1(5,31); M2(53,77) = M1(5,32); M2(53,78) = M1(5,33); M2(53,80) = M1(5,34); M2(53,81) = M1(5,35); M2(53,82) = M1(5,36); M2(53,83) = M1(5,37); M2(53,84) = M1(5,38); M2(53,86) = M1(5,39); M2(53,87) = M1(5,40); M2(53,88) = M1(5,41); M2(53,89) = M1(5,42); M2(53,91) = M1(5,43); M2(53,92) = M1(5,44); M2(53,94) = M1(5,45); M2(53,96) = M1(5,46); M2(53,97) = M1(5,47); M2(53,99) = M1(5,48); M2(53,102) = M1(5,49); M2(53,103) = M1(5,50); M2(53,104) = M1(5,51); M2(53,105) = M1(5,52); M2(53,106) = M1(5,53); M2(53,108) = M1(5,54); M2(53,109) = M1(5,55); M2(53,110) = M1(5,56); M2(53,111) = M1(5,57); M2(53,113) = M1(5,58); M2(53,114) = M1(5,59); M2(53,115) = M1(5,60); M2(53,117) = M1(5,61); M2(53,118) = M1(5,62); M2(53,120) = M1(5,63); M2(53,123) = M1(5,64); M2(53,124) = M1(5,65); M2(53,125) = M1(5,66); M2(53,126) = M1(5,67); M2(53,128) = M1(5,68); M2(53,129) = M1(5,69); M2(53,130) = M1(5,70); M2(53,132) = M1(5,71); M2(53,133) = M1(5,72); M2(53,135) = M1(5,73); M2(53,138) = M1(5,74); M2(53,139) = M1(5,75); M2(53,140) = M1(5,76); M2(53,142) = M1(5,77); M2(53,143) = M1(5,78); M2(53,145) = M1(5,79); M2(53,148) = M1(5,80); M2(53,149) = M1(5,81); M2(53,151) = M1(5,82); M2(53,154) = M1(5,83); M2(54,44) = M1(6,6); M2(54,55) = M1(6,15); M2(54,56) = M1(6,16); M2(54,57) = M1(6,17); M2(54,59) = M1(6,18); M2(54,60) = M1(6,19); M2(54,61) = M1(6,20); M2(54,62) = M1(6,21); M2(54,64) = M1(6,22); M2(54,65) = M1(6,23); M2(54,66) = M1(6,24); M2(54,68) = M1(6,25); M2(54,69) = M1(6,26); M2(54,71) = M1(6,27); M2(54,73) = M1(6,28); M2(54,74) = M1(6,29); M2(54,75) = M1(6,30); M2(54,76) = M1(6,31); M2(54,77) = M1(6,32); M2(54,78) = M1(6,33); M2(54,80) = M1(6,34); M2(54,81) = M1(6,35); M2(54,82) = M1(6,36); M2(54,83) = M1(6,37); M2(54,84) = M1(6,38); M2(54,86) = M1(6,39); M2(54,87) = M1(6,40); M2(54,88) = M1(6,41); M2(54,89) = M1(6,42); M2(54,91) = M1(6,43); M2(54,92) = M1(6,44); M2(54,94) = M1(6,45); M2(54,96) = M1(6,46); M2(54,97) = M1(6,47); M2(54,99) = M1(6,48); M2(54,102) = M1(6,49); M2(54,103) = M1(6,50); M2(54,104) = M1(6,51); M2(54,105) = M1(6,52); M2(54,106) = M1(6,53); M2(54,108) = M1(6,54); M2(54,109) = M1(6,55); M2(54,110) = M1(6,56); M2(54,111) = M1(6,57); M2(54,113) = M1(6,58); M2(54,114) = M1(6,59); M2(54,115) = M1(6,60); M2(54,117) = M1(6,61); M2(54,118) = M1(6,62); M2(54,120) = M1(6,63); M2(54,123) = M1(6,64); M2(54,124) = M1(6,65); M2(54,125) = M1(6,66); M2(54,126) = M1(6,67); M2(54,128) = M1(6,68); M2(54,129) = M1(6,69); M2(54,130) = M1(6,70); M2(54,132) = M1(6,71); M2(54,133) = M1(6,72); M2(54,135) = M1(6,73); M2(54,138) = M1(6,74); M2(54,139) = M1(6,75); M2(54,140) = M1(6,76); M2(54,142) = M1(6,77); M2(54,143) = M1(6,78); M2(54,145) = M1(6,79); M2(54,148) = M1(6,80); M2(54,149) = M1(6,81); M2(54,151) = M1(6,82); M2(54,154) = M1(6,83); M2(55,46) = M1(7,7); M2(55,55) = M1(7,15); M2(55,56) = M1(7,16); M2(55,57) = M1(7,17); M2(55,59) = M1(7,18); M2(55,60) = M1(7,19); M2(55,61) = M1(7,20); M2(55,62) = M1(7,21); M2(55,64) = M1(7,22); M2(55,65) = M1(7,23); M2(55,66) = M1(7,24); M2(55,68) = M1(7,25); M2(55,69) = M1(7,26); M2(55,71) = M1(7,27); M2(55,73) = M1(7,28); M2(55,74) = M1(7,29); M2(55,75) = M1(7,30); M2(55,76) = M1(7,31); M2(55,77) = M1(7,32); M2(55,78) = M1(7,33); M2(55,80) = M1(7,34); M2(55,81) = M1(7,35); M2(55,82) = M1(7,36); M2(55,83) = M1(7,37); M2(55,84) = M1(7,38); M2(55,86) = M1(7,39); M2(55,87) = M1(7,40); M2(55,88) = M1(7,41); M2(55,89) = M1(7,42); M2(55,91) = M1(7,43); M2(55,92) = M1(7,44); M2(55,94) = M1(7,45); M2(55,96) = M1(7,46); M2(55,97) = M1(7,47); M2(55,99) = M1(7,48); M2(55,102) = M1(7,49); M2(55,103) = M1(7,50); M2(55,104) = M1(7,51); M2(55,105) = M1(7,52); M2(55,106) = M1(7,53); M2(55,108) = M1(7,54); M2(55,109) = M1(7,55); M2(55,110) = M1(7,56); M2(55,111) = M1(7,57); M2(55,113) = M1(7,58); M2(55,114) = M1(7,59); M2(55,115) = M1(7,60); M2(55,117) = M1(7,61); M2(55,118) = M1(7,62); M2(55,120) = M1(7,63); M2(55,123) = M1(7,64); M2(55,124) = M1(7,65); M2(55,125) = M1(7,66); M2(55,126) = M1(7,67); M2(55,128) = M1(7,68); M2(55,129) = M1(7,69); M2(55,130) = M1(7,70); M2(55,132) = M1(7,71); M2(55,133) = M1(7,72); M2(55,135) = M1(7,73); M2(55,138) = M1(7,74); M2(55,139) = M1(7,75); M2(55,140) = M1(7,76); M2(55,142) = M1(7,77); M2(55,143) = M1(7,78); M2(55,145) = M1(7,79); M2(55,148) = M1(7,80); M2(55,149) = M1(7,81); M2(55,151) = M1(7,82); M2(55,154) = M1(7,83); M2(56,47) = M1(8,8); M2(56,55) = M1(8,15); M2(56,56) = M1(8,16); M2(56,57) = M1(8,17); M2(56,59) = M1(8,18); M2(56,60) = M1(8,19); M2(56,61) = M1(8,20); M2(56,62) = M1(8,21); M2(56,64) = M1(8,22); M2(56,65) = M1(8,23); M2(56,66) = M1(8,24); M2(56,68) = M1(8,25); M2(56,69) = M1(8,26); M2(56,71) = M1(8,27); M2(56,73) = M1(8,28); M2(56,74) = M1(8,29); M2(56,75) = M1(8,30); M2(56,76) = M1(8,31); M2(56,77) = M1(8,32); M2(56,78) = M1(8,33); M2(56,80) = M1(8,34); M2(56,81) = M1(8,35); M2(56,82) = M1(8,36); M2(56,83) = M1(8,37); M2(56,84) = M1(8,38); M2(56,86) = M1(8,39); M2(56,87) = M1(8,40); M2(56,88) = M1(8,41); M2(56,89) = M1(8,42); M2(56,91) = M1(8,43); M2(56,92) = M1(8,44); M2(56,94) = M1(8,45); M2(56,96) = M1(8,46); M2(56,97) = M1(8,47); M2(56,99) = M1(8,48); M2(56,102) = M1(8,49); M2(56,103) = M1(8,50); M2(56,104) = M1(8,51); M2(56,105) = M1(8,52); M2(56,106) = M1(8,53); M2(56,108) = M1(8,54); M2(56,109) = M1(8,55); M2(56,110) = M1(8,56); M2(56,111) = M1(8,57); M2(56,113) = M1(8,58); M2(56,114) = M1(8,59); M2(56,115) = M1(8,60); M2(56,117) = M1(8,61); M2(56,118) = M1(8,62); M2(56,120) = M1(8,63); M2(56,123) = M1(8,64); M2(56,124) = M1(8,65); M2(56,125) = M1(8,66); M2(56,126) = M1(8,67); M2(56,128) = M1(8,68); M2(56,129) = M1(8,69); M2(56,130) = M1(8,70); M2(56,132) = M1(8,71); M2(56,133) = M1(8,72); M2(56,135) = M1(8,73); M2(56,138) = M1(8,74); M2(56,139) = M1(8,75); M2(56,140) = M1(8,76); M2(56,142) = M1(8,77); M2(56,143) = M1(8,78); M2(56,145) = M1(8,79); M2(56,148) = M1(8,80); M2(56,149) = M1(8,81); M2(56,151) = M1(8,82); M2(56,154) = M1(8,83); M2(57,48) = M1(9,9); M2(57,55) = M1(9,15); M2(57,56) = M1(9,16); M2(57,57) = M1(9,17); M2(57,59) = M1(9,18); M2(57,60) = M1(9,19); M2(57,61) = M1(9,20); M2(57,62) = M1(9,21); M2(57,64) = M1(9,22); M2(57,65) = M1(9,23); M2(57,66) = M1(9,24); M2(57,68) = M1(9,25); M2(57,69) = M1(9,26); M2(57,71) = M1(9,27); M2(57,73) = M1(9,28); M2(57,74) = M1(9,29); M2(57,75) = M1(9,30); M2(57,76) = M1(9,31); M2(57,77) = M1(9,32); M2(57,78) = M1(9,33); M2(57,80) = M1(9,34); M2(57,81) = M1(9,35); M2(57,82) = M1(9,36); M2(57,83) = M1(9,37); M2(57,84) = M1(9,38); M2(57,86) = M1(9,39); M2(57,87) = M1(9,40); M2(57,88) = M1(9,41); M2(57,89) = M1(9,42); M2(57,91) = M1(9,43); M2(57,92) = M1(9,44); M2(57,94) = M1(9,45); M2(57,96) = M1(9,46); M2(57,97) = M1(9,47); M2(57,99) = M1(9,48); M2(57,102) = M1(9,49); M2(57,103) = M1(9,50); M2(57,104) = M1(9,51); M2(57,105) = M1(9,52); M2(57,106) = M1(9,53); M2(57,108) = M1(9,54); M2(57,109) = M1(9,55); M2(57,110) = M1(9,56); M2(57,111) = M1(9,57); M2(57,113) = M1(9,58); M2(57,114) = M1(9,59); M2(57,115) = M1(9,60); M2(57,117) = M1(9,61); M2(57,118) = M1(9,62); M2(57,120) = M1(9,63); M2(57,123) = M1(9,64); M2(57,124) = M1(9,65); M2(57,125) = M1(9,66); M2(57,126) = M1(9,67); M2(57,128) = M1(9,68); M2(57,129) = M1(9,69); M2(57,130) = M1(9,70); M2(57,132) = M1(9,71); M2(57,133) = M1(9,72); M2(57,135) = M1(9,73); M2(57,138) = M1(9,74); M2(57,139) = M1(9,75); M2(57,140) = M1(9,76); M2(57,142) = M1(9,77); M2(57,143) = M1(9,78); M2(57,145) = M1(9,79); M2(57,148) = M1(9,80); M2(57,149) = M1(9,81); M2(57,151) = M1(9,82); M2(57,154) = M1(9,83); M2(58,49) = M1(10,10); M2(58,55) = M1(10,15); M2(58,56) = M1(10,16); M2(58,57) = M1(10,17); M2(58,59) = M1(10,18); M2(58,60) = M1(10,19); M2(58,61) = M1(10,20); M2(58,62) = M1(10,21); M2(58,64) = M1(10,22); M2(58,65) = M1(10,23); M2(58,66) = M1(10,24); M2(58,68) = M1(10,25); M2(58,69) = M1(10,26); M2(58,71) = M1(10,27); M2(58,73) = M1(10,28); M2(58,74) = M1(10,29); M2(58,75) = M1(10,30); M2(58,76) = M1(10,31); M2(58,77) = M1(10,32); M2(58,78) = M1(10,33); M2(58,80) = M1(10,34); M2(58,81) = M1(10,35); M2(58,82) = M1(10,36); M2(58,83) = M1(10,37); M2(58,84) = M1(10,38); M2(58,86) = M1(10,39); M2(58,87) = M1(10,40); M2(58,88) = M1(10,41); M2(58,89) = M1(10,42); M2(58,91) = M1(10,43); M2(58,92) = M1(10,44); M2(58,94) = M1(10,45); M2(58,96) = M1(10,46); M2(58,97) = M1(10,47); M2(58,99) = M1(10,48); M2(58,102) = M1(10,49); M2(58,103) = M1(10,50); M2(58,104) = M1(10,51); M2(58,105) = M1(10,52); M2(58,106) = M1(10,53); M2(58,108) = M1(10,54); M2(58,109) = M1(10,55); M2(58,110) = M1(10,56); M2(58,111) = M1(10,57); M2(58,113) = M1(10,58); M2(58,114) = M1(10,59); M2(58,115) = M1(10,60); M2(58,117) = M1(10,61); M2(58,118) = M1(10,62); M2(58,120) = M1(10,63); M2(58,123) = M1(10,64); M2(58,124) = M1(10,65); M2(58,125) = M1(10,66); M2(58,126) = M1(10,67); M2(58,128) = M1(10,68); M2(58,129) = M1(10,69); M2(58,130) = M1(10,70); M2(58,132) = M1(10,71); M2(58,133) = M1(10,72); M2(58,135) = M1(10,73); M2(58,138) = M1(10,74); M2(58,139) = M1(10,75); M2(58,140) = M1(10,76); M2(58,142) = M1(10,77); M2(58,143) = M1(10,78); M2(58,145) = M1(10,79); M2(58,148) = M1(10,80); M2(58,149) = M1(10,81); M2(58,151) = M1(10,82); M2(58,154) = M1(10,83); M2(59,50) = M1(11,11); M2(59,55) = M1(11,15); M2(59,56) = M1(11,16); M2(59,57) = M1(11,17); M2(59,59) = M1(11,18); M2(59,60) = M1(11,19); M2(59,61) = M1(11,20); M2(59,62) = M1(11,21); M2(59,64) = M1(11,22); M2(59,65) = M1(11,23); M2(59,66) = M1(11,24); M2(59,68) = M1(11,25); M2(59,69) = M1(11,26); M2(59,71) = M1(11,27); M2(59,73) = M1(11,28); M2(59,74) = M1(11,29); M2(59,75) = M1(11,30); M2(59,76) = M1(11,31); M2(59,77) = M1(11,32); M2(59,78) = M1(11,33); M2(59,80) = M1(11,34); M2(59,81) = M1(11,35); M2(59,82) = M1(11,36); M2(59,83) = M1(11,37); M2(59,84) = M1(11,38); M2(59,86) = M1(11,39); M2(59,87) = M1(11,40); M2(59,88) = M1(11,41); M2(59,89) = M1(11,42); M2(59,91) = M1(11,43); M2(59,92) = M1(11,44); M2(59,94) = M1(11,45); M2(59,96) = M1(11,46); M2(59,97) = M1(11,47); M2(59,99) = M1(11,48); M2(59,102) = M1(11,49); M2(59,103) = M1(11,50); M2(59,104) = M1(11,51); M2(59,105) = M1(11,52); M2(59,106) = M1(11,53); M2(59,108) = M1(11,54); M2(59,109) = M1(11,55); M2(59,110) = M1(11,56); M2(59,111) = M1(11,57); M2(59,113) = M1(11,58); M2(59,114) = M1(11,59); M2(59,115) = M1(11,60); M2(59,117) = M1(11,61); M2(59,118) = M1(11,62); M2(59,120) = M1(11,63); M2(59,123) = M1(11,64); M2(59,124) = M1(11,65); M2(59,125) = M1(11,66); M2(59,126) = M1(11,67); M2(59,128) = M1(11,68); M2(59,129) = M1(11,69); M2(59,130) = M1(11,70); M2(59,132) = M1(11,71); M2(59,133) = M1(11,72); M2(59,135) = M1(11,73); M2(59,138) = M1(11,74); M2(59,139) = M1(11,75); M2(59,140) = M1(11,76); M2(59,142) = M1(11,77); M2(59,143) = M1(11,78); M2(59,145) = M1(11,79); M2(59,148) = M1(11,80); M2(59,149) = M1(11,81); M2(59,151) = M1(11,82); M2(59,154) = M1(11,83); M2(60,51) = M1(12,12); M2(60,55) = M1(12,15); M2(60,56) = M1(12,16); M2(60,57) = M1(12,17); M2(60,59) = M1(12,18); M2(60,60) = M1(12,19); M2(60,61) = M1(12,20); M2(60,62) = M1(12,21); M2(60,64) = M1(12,22); M2(60,65) = M1(12,23); M2(60,66) = M1(12,24); M2(60,68) = M1(12,25); M2(60,69) = M1(12,26); M2(60,71) = M1(12,27); M2(60,73) = M1(12,28); M2(60,74) = M1(12,29); M2(60,75) = M1(12,30); M2(60,76) = M1(12,31); M2(60,77) = M1(12,32); M2(60,78) = M1(12,33); M2(60,80) = M1(12,34); M2(60,81) = M1(12,35); M2(60,82) = M1(12,36); M2(60,83) = M1(12,37); M2(60,84) = M1(12,38); M2(60,86) = M1(12,39); M2(60,87) = M1(12,40); M2(60,88) = M1(12,41); M2(60,89) = M1(12,42); M2(60,91) = M1(12,43); M2(60,92) = M1(12,44); M2(60,94) = M1(12,45); M2(60,96) = M1(12,46); M2(60,97) = M1(12,47); M2(60,99) = M1(12,48); M2(60,102) = M1(12,49); M2(60,103) = M1(12,50); M2(60,104) = M1(12,51); M2(60,105) = M1(12,52); M2(60,106) = M1(12,53); M2(60,108) = M1(12,54); M2(60,109) = M1(12,55); M2(60,110) = M1(12,56); M2(60,111) = M1(12,57); M2(60,113) = M1(12,58); M2(60,114) = M1(12,59); M2(60,115) = M1(12,60); M2(60,117) = M1(12,61); M2(60,118) = M1(12,62); M2(60,120) = M1(12,63); M2(60,123) = M1(12,64); M2(60,124) = M1(12,65); M2(60,125) = M1(12,66); M2(60,126) = M1(12,67); M2(60,128) = M1(12,68); M2(60,129) = M1(12,69); M2(60,130) = M1(12,70); M2(60,132) = M1(12,71); M2(60,133) = M1(12,72); M2(60,135) = M1(12,73); M2(60,138) = M1(12,74); M2(60,139) = M1(12,75); M2(60,140) = M1(12,76); M2(60,142) = M1(12,77); M2(60,143) = M1(12,78); M2(60,145) = M1(12,79); M2(60,148) = M1(12,80); M2(60,149) = M1(12,81); M2(60,151) = M1(12,82); M2(60,154) = M1(12,83); M2(61,53) = M1(13,13); M2(61,55) = M1(13,15); M2(61,56) = M1(13,16); M2(61,57) = M1(13,17); M2(61,59) = M1(13,18); M2(61,60) = M1(13,19); M2(61,61) = M1(13,20); M2(61,62) = M1(13,21); M2(61,64) = M1(13,22); M2(61,65) = M1(13,23); M2(61,66) = M1(13,24); M2(61,68) = M1(13,25); M2(61,69) = M1(13,26); M2(61,71) = M1(13,27); M2(61,73) = M1(13,28); M2(61,74) = M1(13,29); M2(61,75) = M1(13,30); M2(61,76) = M1(13,31); M2(61,77) = M1(13,32); M2(61,78) = M1(13,33); M2(61,80) = M1(13,34); M2(61,81) = M1(13,35); M2(61,82) = M1(13,36); M2(61,83) = M1(13,37); M2(61,84) = M1(13,38); M2(61,86) = M1(13,39); M2(61,87) = M1(13,40); M2(61,88) = M1(13,41); M2(61,89) = M1(13,42); M2(61,91) = M1(13,43); M2(61,92) = M1(13,44); M2(61,94) = M1(13,45); M2(61,96) = M1(13,46); M2(61,97) = M1(13,47); M2(61,99) = M1(13,48); M2(61,102) = M1(13,49); M2(61,103) = M1(13,50); M2(61,104) = M1(13,51); M2(61,105) = M1(13,52); M2(61,106) = M1(13,53); M2(61,108) = M1(13,54); M2(61,109) = M1(13,55); M2(61,110) = M1(13,56); M2(61,111) = M1(13,57); M2(61,113) = M1(13,58); M2(61,114) = M1(13,59); M2(61,115) = M1(13,60); M2(61,117) = M1(13,61); M2(61,118) = M1(13,62); M2(61,120) = M1(13,63); M2(61,123) = M1(13,64); M2(61,124) = M1(13,65); M2(61,125) = M1(13,66); M2(61,126) = M1(13,67); M2(61,128) = M1(13,68); M2(61,129) = M1(13,69); M2(61,130) = M1(13,70); M2(61,132) = M1(13,71); M2(61,133) = M1(13,72); M2(61,135) = M1(13,73); M2(61,138) = M1(13,74); M2(61,139) = M1(13,75); M2(61,140) = M1(13,76); M2(61,142) = M1(13,77); M2(61,143) = M1(13,78); M2(61,145) = M1(13,79); M2(61,148) = M1(13,80); M2(61,149) = M1(13,81); M2(61,151) = M1(13,82); M2(61,154) = M1(13,83); M2(62,54) = M1(14,14); M2(62,55) = M1(14,15); M2(62,56) = M1(14,16); M2(62,57) = M1(14,17); M2(62,59) = M1(14,18); M2(62,60) = M1(14,19); M2(62,61) = M1(14,20); M2(62,62) = M1(14,21); M2(62,64) = M1(14,22); M2(62,65) = M1(14,23); M2(62,66) = M1(14,24); M2(62,68) = M1(14,25); M2(62,69) = M1(14,26); M2(62,71) = M1(14,27); M2(62,73) = M1(14,28); M2(62,74) = M1(14,29); M2(62,75) = M1(14,30); M2(62,76) = M1(14,31); M2(62,77) = M1(14,32); M2(62,78) = M1(14,33); M2(62,80) = M1(14,34); M2(62,81) = M1(14,35); M2(62,82) = M1(14,36); M2(62,83) = M1(14,37); M2(62,84) = M1(14,38); M2(62,86) = M1(14,39); M2(62,87) = M1(14,40); M2(62,88) = M1(14,41); M2(62,89) = M1(14,42); M2(62,91) = M1(14,43); M2(62,92) = M1(14,44); M2(62,94) = M1(14,45); M2(62,96) = M1(14,46); M2(62,97) = M1(14,47); M2(62,99) = M1(14,48); M2(62,102) = M1(14,49); M2(62,103) = M1(14,50); M2(62,104) = M1(14,51); M2(62,105) = M1(14,52); M2(62,106) = M1(14,53); M2(62,108) = M1(14,54); M2(62,109) = M1(14,55); M2(62,110) = M1(14,56); M2(62,111) = M1(14,57); M2(62,113) = M1(14,58); M2(62,114) = M1(14,59); M2(62,115) = M1(14,60); M2(62,117) = M1(14,61); M2(62,118) = M1(14,62); M2(62,120) = M1(14,63); M2(62,123) = M1(14,64); M2(62,124) = M1(14,65); M2(62,125) = M1(14,66); M2(62,126) = M1(14,67); M2(62,128) = M1(14,68); M2(62,129) = M1(14,69); M2(62,130) = M1(14,70); M2(62,132) = M1(14,71); M2(62,133) = M1(14,72); M2(62,135) = M1(14,73); M2(62,138) = M1(14,74); M2(62,139) = M1(14,75); M2(62,140) = M1(14,76); M2(62,142) = M1(14,77); M2(62,143) = M1(14,78); M2(62,145) = M1(14,79); M2(62,148) = M1(14,80); M2(62,149) = M1(14,81); M2(62,151) = M1(14,82); M2(62,154) = M1(14,83); M2(63,37) = M1(0,0); M2(63,54) = M1(0,15); M2(63,55) = M1(0,16); M2(63,56) = M1(0,17); M2(63,58) = M1(0,18); M2(63,59) = M1(0,19); M2(63,60) = M1(0,20); M2(63,61) = M1(0,21); M2(63,63) = M1(0,22); M2(63,64) = M1(0,23); M2(63,65) = M1(0,24); M2(63,67) = M1(0,25); M2(63,68) = M1(0,26); M2(63,70) = M1(0,27); M2(63,72) = M1(0,28); M2(63,73) = M1(0,29); M2(63,74) = M1(0,30); M2(63,75) = M1(0,31); M2(63,76) = M1(0,32); M2(63,77) = M1(0,33); M2(63,79) = M1(0,34); M2(63,80) = M1(0,35); M2(63,81) = M1(0,36); M2(63,82) = M1(0,37); M2(63,83) = M1(0,38); M2(63,85) = M1(0,39); M2(63,86) = M1(0,40); M2(63,87) = M1(0,41); M2(63,88) = M1(0,42); M2(63,90) = M1(0,43); M2(63,91) = M1(0,44); M2(63,92) = M1(0,45); M2(63,95) = M1(0,46); M2(63,96) = M1(0,47); M2(63,98) = M1(0,48); M2(63,101) = M1(0,49); M2(63,102) = M1(0,50); M2(63,103) = M1(0,51); M2(63,104) = M1(0,52); M2(63,105) = M1(0,53); M2(63,107) = M1(0,54); M2(63,108) = M1(0,55); M2(63,109) = M1(0,56); M2(63,110) = M1(0,57); M2(63,112) = M1(0,58); M2(63,113) = M1(0,59); M2(63,114) = M1(0,60); M2(63,116) = M1(0,61); M2(63,117) = M1(0,62); M2(63,119) = M1(0,63); M2(63,122) = M1(0,64); M2(63,123) = M1(0,65); M2(63,124) = M1(0,66); M2(63,125) = M1(0,67); M2(63,127) = M1(0,68); M2(63,128) = M1(0,69); M2(63,129) = M1(0,70); M2(63,131) = M1(0,71); M2(63,132) = M1(0,72); M2(63,134) = M1(0,73); M2(63,137) = M1(0,74); M2(63,138) = M1(0,75); M2(63,139) = M1(0,76); M2(63,141) = M1(0,77); M2(63,142) = M1(0,78); M2(63,144) = M1(0,79); M2(63,147) = M1(0,80); M2(63,148) = M1(0,81); M2(63,150) = M1(0,82); M2(63,153) = M1(0,83); M2(64,38) = M1(1,1); M2(64,54) = M1(1,15); M2(64,55) = M1(1,16); M2(64,56) = M1(1,17); M2(64,58) = M1(1,18); M2(64,59) = M1(1,19); M2(64,60) = M1(1,20); M2(64,61) = M1(1,21); M2(64,63) = M1(1,22); M2(64,64) = M1(1,23); M2(64,65) = M1(1,24); M2(64,67) = M1(1,25); M2(64,68) = M1(1,26); M2(64,70) = M1(1,27); M2(64,72) = M1(1,28); M2(64,73) = M1(1,29); M2(64,74) = M1(1,30); M2(64,75) = M1(1,31); M2(64,76) = M1(1,32); M2(64,77) = M1(1,33); M2(64,79) = M1(1,34); M2(64,80) = M1(1,35); M2(64,81) = M1(1,36); M2(64,82) = M1(1,37); M2(64,83) = M1(1,38); M2(64,85) = M1(1,39); M2(64,86) = M1(1,40); M2(64,87) = M1(1,41); M2(64,88) = M1(1,42); M2(64,90) = M1(1,43); M2(64,91) = M1(1,44); M2(64,92) = M1(1,45); M2(64,95) = M1(1,46); M2(64,96) = M1(1,47); M2(64,98) = M1(1,48); M2(64,101) = M1(1,49); M2(64,102) = M1(1,50); M2(64,103) = M1(1,51); M2(64,104) = M1(1,52); M2(64,105) = M1(1,53); M2(64,107) = M1(1,54); M2(64,108) = M1(1,55); M2(64,109) = M1(1,56); M2(64,110) = M1(1,57); M2(64,112) = M1(1,58); M2(64,113) = M1(1,59); M2(64,114) = M1(1,60); M2(64,116) = M1(1,61); M2(64,117) = M1(1,62); M2(64,119) = M1(1,63); M2(64,122) = M1(1,64); M2(64,123) = M1(1,65); M2(64,124) = M1(1,66); M2(64,125) = M1(1,67); M2(64,127) = M1(1,68); M2(64,128) = M1(1,69); M2(64,129) = M1(1,70); M2(64,131) = M1(1,71); M2(64,132) = M1(1,72); M2(64,134) = M1(1,73); M2(64,137) = M1(1,74); M2(64,138) = M1(1,75); M2(64,139) = M1(1,76); M2(64,141) = M1(1,77); M2(64,142) = M1(1,78); M2(64,144) = M1(1,79); M2(64,147) = M1(1,80); M2(64,148) = M1(1,81); M2(64,150) = M1(1,82); M2(64,153) = M1(1,83); M2(65,39) = M1(2,2); M2(65,54) = M1(2,15); M2(65,55) = M1(2,16); M2(65,56) = M1(2,17); M2(65,58) = M1(2,18); M2(65,59) = M1(2,19); M2(65,60) = M1(2,20); M2(65,61) = M1(2,21); M2(65,63) = M1(2,22); M2(65,64) = M1(2,23); M2(65,65) = M1(2,24); M2(65,67) = M1(2,25); M2(65,68) = M1(2,26); M2(65,70) = M1(2,27); M2(65,72) = M1(2,28); M2(65,73) = M1(2,29); M2(65,74) = M1(2,30); M2(65,75) = M1(2,31); M2(65,76) = M1(2,32); M2(65,77) = M1(2,33); M2(65,79) = M1(2,34); M2(65,80) = M1(2,35); M2(65,81) = M1(2,36); M2(65,82) = M1(2,37); M2(65,83) = M1(2,38); M2(65,85) = M1(2,39); M2(65,86) = M1(2,40); M2(65,87) = M1(2,41); M2(65,88) = M1(2,42); M2(65,90) = M1(2,43); M2(65,91) = M1(2,44); M2(65,92) = M1(2,45); M2(65,95) = M1(2,46); M2(65,96) = M1(2,47); M2(65,98) = M1(2,48); M2(65,101) = M1(2,49); M2(65,102) = M1(2,50); M2(65,103) = M1(2,51); M2(65,104) = M1(2,52); M2(65,105) = M1(2,53); M2(65,107) = M1(2,54); M2(65,108) = M1(2,55); M2(65,109) = M1(2,56); M2(65,110) = M1(2,57); M2(65,112) = M1(2,58); M2(65,113) = M1(2,59); M2(65,114) = M1(2,60); M2(65,116) = M1(2,61); M2(65,117) = M1(2,62); M2(65,119) = M1(2,63); M2(65,122) = M1(2,64); M2(65,123) = M1(2,65); M2(65,124) = M1(2,66); M2(65,125) = M1(2,67); M2(65,127) = M1(2,68); M2(65,128) = M1(2,69); M2(65,129) = M1(2,70); M2(65,131) = M1(2,71); M2(65,132) = M1(2,72); M2(65,134) = M1(2,73); M2(65,137) = M1(2,74); M2(65,138) = M1(2,75); M2(65,139) = M1(2,76); M2(65,141) = M1(2,77); M2(65,142) = M1(2,78); M2(65,144) = M1(2,79); M2(65,147) = M1(2,80); M2(65,148) = M1(2,81); M2(65,150) = M1(2,82); M2(65,153) = M1(2,83); M2(66,40) = M1(3,3); M2(66,54) = M1(3,15); M2(66,55) = M1(3,16); M2(66,56) = M1(3,17); M2(66,58) = M1(3,18); M2(66,59) = M1(3,19); M2(66,60) = M1(3,20); M2(66,61) = M1(3,21); M2(66,63) = M1(3,22); M2(66,64) = M1(3,23); M2(66,65) = M1(3,24); M2(66,67) = M1(3,25); M2(66,68) = M1(3,26); M2(66,70) = M1(3,27); M2(66,72) = M1(3,28); M2(66,73) = M1(3,29); M2(66,74) = M1(3,30); M2(66,75) = M1(3,31); M2(66,76) = M1(3,32); M2(66,77) = M1(3,33); M2(66,79) = M1(3,34); M2(66,80) = M1(3,35); M2(66,81) = M1(3,36); M2(66,82) = M1(3,37); M2(66,83) = M1(3,38); M2(66,85) = M1(3,39); M2(66,86) = M1(3,40); M2(66,87) = M1(3,41); M2(66,88) = M1(3,42); M2(66,90) = M1(3,43); M2(66,91) = M1(3,44); M2(66,92) = M1(3,45); M2(66,95) = M1(3,46); M2(66,96) = M1(3,47); M2(66,98) = M1(3,48); M2(66,101) = M1(3,49); M2(66,102) = M1(3,50); M2(66,103) = M1(3,51); M2(66,104) = M1(3,52); M2(66,105) = M1(3,53); M2(66,107) = M1(3,54); M2(66,108) = M1(3,55); M2(66,109) = M1(3,56); M2(66,110) = M1(3,57); M2(66,112) = M1(3,58); M2(66,113) = M1(3,59); M2(66,114) = M1(3,60); M2(66,116) = M1(3,61); M2(66,117) = M1(3,62); M2(66,119) = M1(3,63); M2(66,122) = M1(3,64); M2(66,123) = M1(3,65); M2(66,124) = M1(3,66); M2(66,125) = M1(3,67); M2(66,127) = M1(3,68); M2(66,128) = M1(3,69); M2(66,129) = M1(3,70); M2(66,131) = M1(3,71); M2(66,132) = M1(3,72); M2(66,134) = M1(3,73); M2(66,137) = M1(3,74); M2(66,138) = M1(3,75); M2(66,139) = M1(3,76); M2(66,141) = M1(3,77); M2(66,142) = M1(3,78); M2(66,144) = M1(3,79); M2(66,147) = M1(3,80); M2(66,148) = M1(3,81); M2(66,150) = M1(3,82); M2(66,153) = M1(3,83); M2(67,41) = M1(4,4); M2(67,54) = M1(4,15); M2(67,55) = M1(4,16); M2(67,56) = M1(4,17); M2(67,58) = M1(4,18); M2(67,59) = M1(4,19); M2(67,60) = M1(4,20); M2(67,61) = M1(4,21); M2(67,63) = M1(4,22); M2(67,64) = M1(4,23); M2(67,65) = M1(4,24); M2(67,67) = M1(4,25); M2(67,68) = M1(4,26); M2(67,70) = M1(4,27); M2(67,72) = M1(4,28); M2(67,73) = M1(4,29); M2(67,74) = M1(4,30); M2(67,75) = M1(4,31); M2(67,76) = M1(4,32); M2(67,77) = M1(4,33); M2(67,79) = M1(4,34); M2(67,80) = M1(4,35); M2(67,81) = M1(4,36); M2(67,82) = M1(4,37); M2(67,83) = M1(4,38); M2(67,85) = M1(4,39); M2(67,86) = M1(4,40); M2(67,87) = M1(4,41); M2(67,88) = M1(4,42); M2(67,90) = M1(4,43); M2(67,91) = M1(4,44); M2(67,92) = M1(4,45); M2(67,95) = M1(4,46); M2(67,96) = M1(4,47); M2(67,98) = M1(4,48); M2(67,101) = M1(4,49); M2(67,102) = M1(4,50); M2(67,103) = M1(4,51); M2(67,104) = M1(4,52); M2(67,105) = M1(4,53); M2(67,107) = M1(4,54); M2(67,108) = M1(4,55); M2(67,109) = M1(4,56); M2(67,110) = M1(4,57); M2(67,112) = M1(4,58); M2(67,113) = M1(4,59); M2(67,114) = M1(4,60); M2(67,116) = M1(4,61); M2(67,117) = M1(4,62); M2(67,119) = M1(4,63); M2(67,122) = M1(4,64); M2(67,123) = M1(4,65); M2(67,124) = M1(4,66); M2(67,125) = M1(4,67); M2(67,127) = M1(4,68); M2(67,128) = M1(4,69); M2(67,129) = M1(4,70); M2(67,131) = M1(4,71); M2(67,132) = M1(4,72); M2(67,134) = M1(4,73); M2(67,137) = M1(4,74); M2(67,138) = M1(4,75); M2(67,139) = M1(4,76); M2(67,141) = M1(4,77); M2(67,142) = M1(4,78); M2(67,144) = M1(4,79); M2(67,147) = M1(4,80); M2(67,148) = M1(4,81); M2(67,150) = M1(4,82); M2(67,153) = M1(4,83); M2(68,42) = M1(5,5); M2(68,54) = M1(5,15); M2(68,55) = M1(5,16); M2(68,56) = M1(5,17); M2(68,58) = M1(5,18); M2(68,59) = M1(5,19); M2(68,60) = M1(5,20); M2(68,61) = M1(5,21); M2(68,63) = M1(5,22); M2(68,64) = M1(5,23); M2(68,65) = M1(5,24); M2(68,67) = M1(5,25); M2(68,68) = M1(5,26); M2(68,70) = M1(5,27); M2(68,72) = M1(5,28); M2(68,73) = M1(5,29); M2(68,74) = M1(5,30); M2(68,75) = M1(5,31); M2(68,76) = M1(5,32); M2(68,77) = M1(5,33); M2(68,79) = M1(5,34); M2(68,80) = M1(5,35); M2(68,81) = M1(5,36); M2(68,82) = M1(5,37); M2(68,83) = M1(5,38); M2(68,85) = M1(5,39); M2(68,86) = M1(5,40); M2(68,87) = M1(5,41); M2(68,88) = M1(5,42); M2(68,90) = M1(5,43); M2(68,91) = M1(5,44); M2(68,92) = M1(5,45); M2(68,95) = M1(5,46); M2(68,96) = M1(5,47); M2(68,98) = M1(5,48); M2(68,101) = M1(5,49); M2(68,102) = M1(5,50); M2(68,103) = M1(5,51); M2(68,104) = M1(5,52); M2(68,105) = M1(5,53); M2(68,107) = M1(5,54); M2(68,108) = M1(5,55); M2(68,109) = M1(5,56); M2(68,110) = M1(5,57); M2(68,112) = M1(5,58); M2(68,113) = M1(5,59); M2(68,114) = M1(5,60); M2(68,116) = M1(5,61); M2(68,117) = M1(5,62); M2(68,119) = M1(5,63); M2(68,122) = M1(5,64); M2(68,123) = M1(5,65); M2(68,124) = M1(5,66); M2(68,125) = M1(5,67); M2(68,127) = M1(5,68); M2(68,128) = M1(5,69); M2(68,129) = M1(5,70); M2(68,131) = M1(5,71); M2(68,132) = M1(5,72); M2(68,134) = M1(5,73); M2(68,137) = M1(5,74); M2(68,138) = M1(5,75); M2(68,139) = M1(5,76); M2(68,141) = M1(5,77); M2(68,142) = M1(5,78); M2(68,144) = M1(5,79); M2(68,147) = M1(5,80); M2(68,148) = M1(5,81); M2(68,150) = M1(5,82); M2(68,153) = M1(5,83); M2(69,43) = M1(6,6); M2(69,54) = M1(6,15); M2(69,55) = M1(6,16); M2(69,56) = M1(6,17); M2(69,58) = M1(6,18); M2(69,59) = M1(6,19); M2(69,60) = M1(6,20); M2(69,61) = M1(6,21); M2(69,63) = M1(6,22); M2(69,64) = M1(6,23); M2(69,65) = M1(6,24); M2(69,67) = M1(6,25); M2(69,68) = M1(6,26); M2(69,70) = M1(6,27); M2(69,72) = M1(6,28); M2(69,73) = M1(6,29); M2(69,74) = M1(6,30); M2(69,75) = M1(6,31); M2(69,76) = M1(6,32); M2(69,77) = M1(6,33); M2(69,79) = M1(6,34); M2(69,80) = M1(6,35); M2(69,81) = M1(6,36); M2(69,82) = M1(6,37); M2(69,83) = M1(6,38); M2(69,85) = M1(6,39); M2(69,86) = M1(6,40); M2(69,87) = M1(6,41); M2(69,88) = M1(6,42); M2(69,90) = M1(6,43); M2(69,91) = M1(6,44); M2(69,92) = M1(6,45); M2(69,95) = M1(6,46); M2(69,96) = M1(6,47); M2(69,98) = M1(6,48); M2(69,101) = M1(6,49); M2(69,102) = M1(6,50); M2(69,103) = M1(6,51); M2(69,104) = M1(6,52); M2(69,105) = M1(6,53); M2(69,107) = M1(6,54); M2(69,108) = M1(6,55); M2(69,109) = M1(6,56); M2(69,110) = M1(6,57); M2(69,112) = M1(6,58); M2(69,113) = M1(6,59); M2(69,114) = M1(6,60); M2(69,116) = M1(6,61); M2(69,117) = M1(6,62); M2(69,119) = M1(6,63); M2(69,122) = M1(6,64); M2(69,123) = M1(6,65); M2(69,124) = M1(6,66); M2(69,125) = M1(6,67); M2(69,127) = M1(6,68); M2(69,128) = M1(6,69); M2(69,129) = M1(6,70); M2(69,131) = M1(6,71); M2(69,132) = M1(6,72); M2(69,134) = M1(6,73); M2(69,137) = M1(6,74); M2(69,138) = M1(6,75); M2(69,139) = M1(6,76); M2(69,141) = M1(6,77); M2(69,142) = M1(6,78); M2(69,144) = M1(6,79); M2(69,147) = M1(6,80); M2(69,148) = M1(6,81); M2(69,150) = M1(6,82); M2(69,153) = M1(6,83); M2(70,45) = M1(7,7); M2(70,54) = M1(7,15); M2(70,55) = M1(7,16); M2(70,56) = M1(7,17); M2(70,58) = M1(7,18); M2(70,59) = M1(7,19); M2(70,60) = M1(7,20); M2(70,61) = M1(7,21); M2(70,63) = M1(7,22); M2(70,64) = M1(7,23); M2(70,65) = M1(7,24); M2(70,67) = M1(7,25); M2(70,68) = M1(7,26); M2(70,70) = M1(7,27); M2(70,72) = M1(7,28); M2(70,73) = M1(7,29); M2(70,74) = M1(7,30); M2(70,75) = M1(7,31); M2(70,76) = M1(7,32); M2(70,77) = M1(7,33); M2(70,79) = M1(7,34); M2(70,80) = M1(7,35); M2(70,81) = M1(7,36); M2(70,82) = M1(7,37); M2(70,83) = M1(7,38); M2(70,85) = M1(7,39); M2(70,86) = M1(7,40); M2(70,87) = M1(7,41); M2(70,88) = M1(7,42); M2(70,90) = M1(7,43); M2(70,91) = M1(7,44); M2(70,92) = M1(7,45); M2(70,95) = M1(7,46); M2(70,96) = M1(7,47); M2(70,98) = M1(7,48); M2(70,101) = M1(7,49); M2(70,102) = M1(7,50); M2(70,103) = M1(7,51); M2(70,104) = M1(7,52); M2(70,105) = M1(7,53); M2(70,107) = M1(7,54); M2(70,108) = M1(7,55); M2(70,109) = M1(7,56); M2(70,110) = M1(7,57); M2(70,112) = M1(7,58); M2(70,113) = M1(7,59); M2(70,114) = M1(7,60); M2(70,116) = M1(7,61); M2(70,117) = M1(7,62); M2(70,119) = M1(7,63); M2(70,122) = M1(7,64); M2(70,123) = M1(7,65); M2(70,124) = M1(7,66); M2(70,125) = M1(7,67); M2(70,127) = M1(7,68); M2(70,128) = M1(7,69); M2(70,129) = M1(7,70); M2(70,131) = M1(7,71); M2(70,132) = M1(7,72); M2(70,134) = M1(7,73); M2(70,137) = M1(7,74); M2(70,138) = M1(7,75); M2(70,139) = M1(7,76); M2(70,141) = M1(7,77); M2(70,142) = M1(7,78); M2(70,144) = M1(7,79); M2(70,147) = M1(7,80); M2(70,148) = M1(7,81); M2(70,150) = M1(7,82); M2(70,153) = M1(7,83); M2(71,46) = M1(8,8); M2(71,54) = M1(8,15); M2(71,55) = M1(8,16); M2(71,56) = M1(8,17); M2(71,58) = M1(8,18); M2(71,59) = M1(8,19); M2(71,60) = M1(8,20); M2(71,61) = M1(8,21); M2(71,63) = M1(8,22); M2(71,64) = M1(8,23); M2(71,65) = M1(8,24); M2(71,67) = M1(8,25); M2(71,68) = M1(8,26); M2(71,70) = M1(8,27); M2(71,72) = M1(8,28); M2(71,73) = M1(8,29); M2(71,74) = M1(8,30); M2(71,75) = M1(8,31); M2(71,76) = M1(8,32); M2(71,77) = M1(8,33); M2(71,79) = M1(8,34); M2(71,80) = M1(8,35); M2(71,81) = M1(8,36); M2(71,82) = M1(8,37); M2(71,83) = M1(8,38); M2(71,85) = M1(8,39); M2(71,86) = M1(8,40); M2(71,87) = M1(8,41); M2(71,88) = M1(8,42); M2(71,90) = M1(8,43); M2(71,91) = M1(8,44); M2(71,92) = M1(8,45); M2(71,95) = M1(8,46); M2(71,96) = M1(8,47); M2(71,98) = M1(8,48); M2(71,101) = M1(8,49); M2(71,102) = M1(8,50); M2(71,103) = M1(8,51); M2(71,104) = M1(8,52); M2(71,105) = M1(8,53); M2(71,107) = M1(8,54); M2(71,108) = M1(8,55); M2(71,109) = M1(8,56); M2(71,110) = M1(8,57); M2(71,112) = M1(8,58); M2(71,113) = M1(8,59); M2(71,114) = M1(8,60); M2(71,116) = M1(8,61); M2(71,117) = M1(8,62); M2(71,119) = M1(8,63); M2(71,122) = M1(8,64); M2(71,123) = M1(8,65); M2(71,124) = M1(8,66); M2(71,125) = M1(8,67); M2(71,127) = M1(8,68); M2(71,128) = M1(8,69); M2(71,129) = M1(8,70); M2(71,131) = M1(8,71); M2(71,132) = M1(8,72); M2(71,134) = M1(8,73); M2(71,137) = M1(8,74); M2(71,138) = M1(8,75); M2(71,139) = M1(8,76); M2(71,141) = M1(8,77); M2(71,142) = M1(8,78); M2(71,144) = M1(8,79); M2(71,147) = M1(8,80); M2(71,148) = M1(8,81); M2(71,150) = M1(8,82); M2(71,153) = M1(8,83); M2(72,47) = M1(9,9); M2(72,54) = M1(9,15); M2(72,55) = M1(9,16); M2(72,56) = M1(9,17); M2(72,58) = M1(9,18); M2(72,59) = M1(9,19); M2(72,60) = M1(9,20); M2(72,61) = M1(9,21); M2(72,63) = M1(9,22); M2(72,64) = M1(9,23); M2(72,65) = M1(9,24); M2(72,67) = M1(9,25); M2(72,68) = M1(9,26); M2(72,70) = M1(9,27); M2(72,72) = M1(9,28); M2(72,73) = M1(9,29); M2(72,74) = M1(9,30); M2(72,75) = M1(9,31); M2(72,76) = M1(9,32); M2(72,77) = M1(9,33); M2(72,79) = M1(9,34); M2(72,80) = M1(9,35); M2(72,81) = M1(9,36); M2(72,82) = M1(9,37); M2(72,83) = M1(9,38); M2(72,85) = M1(9,39); M2(72,86) = M1(9,40); M2(72,87) = M1(9,41); M2(72,88) = M1(9,42); M2(72,90) = M1(9,43); M2(72,91) = M1(9,44); M2(72,92) = M1(9,45); M2(72,95) = M1(9,46); M2(72,96) = M1(9,47); M2(72,98) = M1(9,48); M2(72,101) = M1(9,49); M2(72,102) = M1(9,50); M2(72,103) = M1(9,51); M2(72,104) = M1(9,52); M2(72,105) = M1(9,53); M2(72,107) = M1(9,54); M2(72,108) = M1(9,55); M2(72,109) = M1(9,56); M2(72,110) = M1(9,57); M2(72,112) = M1(9,58); M2(72,113) = M1(9,59); M2(72,114) = M1(9,60); M2(72,116) = M1(9,61); M2(72,117) = M1(9,62); M2(72,119) = M1(9,63); M2(72,122) = M1(9,64); M2(72,123) = M1(9,65); M2(72,124) = M1(9,66); M2(72,125) = M1(9,67); M2(72,127) = M1(9,68); M2(72,128) = M1(9,69); M2(72,129) = M1(9,70); M2(72,131) = M1(9,71); M2(72,132) = M1(9,72); M2(72,134) = M1(9,73); M2(72,137) = M1(9,74); M2(72,138) = M1(9,75); M2(72,139) = M1(9,76); M2(72,141) = M1(9,77); M2(72,142) = M1(9,78); M2(72,144) = M1(9,79); M2(72,147) = M1(9,80); M2(72,148) = M1(9,81); M2(72,150) = M1(9,82); M2(72,153) = M1(9,83); M2(73,48) = M1(10,10); M2(73,54) = M1(10,15); M2(73,55) = M1(10,16); M2(73,56) = M1(10,17); M2(73,58) = M1(10,18); M2(73,59) = M1(10,19); M2(73,60) = M1(10,20); M2(73,61) = M1(10,21); M2(73,63) = M1(10,22); M2(73,64) = M1(10,23); M2(73,65) = M1(10,24); M2(73,67) = M1(10,25); M2(73,68) = M1(10,26); M2(73,70) = M1(10,27); M2(73,72) = M1(10,28); M2(73,73) = M1(10,29); M2(73,74) = M1(10,30); M2(73,75) = M1(10,31); M2(73,76) = M1(10,32); M2(73,77) = M1(10,33); M2(73,79) = M1(10,34); M2(73,80) = M1(10,35); M2(73,81) = M1(10,36); M2(73,82) = M1(10,37); M2(73,83) = M1(10,38); M2(73,85) = M1(10,39); M2(73,86) = M1(10,40); M2(73,87) = M1(10,41); M2(73,88) = M1(10,42); M2(73,90) = M1(10,43); M2(73,91) = M1(10,44); M2(73,92) = M1(10,45); M2(73,95) = M1(10,46); M2(73,96) = M1(10,47); M2(73,98) = M1(10,48); M2(73,101) = M1(10,49); M2(73,102) = M1(10,50); M2(73,103) = M1(10,51); M2(73,104) = M1(10,52); M2(73,105) = M1(10,53); M2(73,107) = M1(10,54); M2(73,108) = M1(10,55); M2(73,109) = M1(10,56); M2(73,110) = M1(10,57); M2(73,112) = M1(10,58); M2(73,113) = M1(10,59); M2(73,114) = M1(10,60); M2(73,116) = M1(10,61); M2(73,117) = M1(10,62); M2(73,119) = M1(10,63); M2(73,122) = M1(10,64); M2(73,123) = M1(10,65); M2(73,124) = M1(10,66); M2(73,125) = M1(10,67); M2(73,127) = M1(10,68); M2(73,128) = M1(10,69); M2(73,129) = M1(10,70); M2(73,131) = M1(10,71); M2(73,132) = M1(10,72); M2(73,134) = M1(10,73); M2(73,137) = M1(10,74); M2(73,138) = M1(10,75); M2(73,139) = M1(10,76); M2(73,141) = M1(10,77); M2(73,142) = M1(10,78); M2(73,144) = M1(10,79); M2(73,147) = M1(10,80); M2(73,148) = M1(10,81); M2(73,150) = M1(10,82); M2(73,153) = M1(10,83); M2(74,49) = M1(11,11); M2(74,54) = M1(11,15); M2(74,55) = M1(11,16); M2(74,56) = M1(11,17); M2(74,58) = M1(11,18); M2(74,59) = M1(11,19); M2(74,60) = M1(11,20); M2(74,61) = M1(11,21); M2(74,63) = M1(11,22); M2(74,64) = M1(11,23); M2(74,65) = M1(11,24); M2(74,67) = M1(11,25); M2(74,68) = M1(11,26); M2(74,70) = M1(11,27); M2(74,72) = M1(11,28); M2(74,73) = M1(11,29); M2(74,74) = M1(11,30); M2(74,75) = M1(11,31); M2(74,76) = M1(11,32); M2(74,77) = M1(11,33); M2(74,79) = M1(11,34); M2(74,80) = M1(11,35); M2(74,81) = M1(11,36); M2(74,82) = M1(11,37); M2(74,83) = M1(11,38); M2(74,85) = M1(11,39); M2(74,86) = M1(11,40); M2(74,87) = M1(11,41); M2(74,88) = M1(11,42); M2(74,90) = M1(11,43); M2(74,91) = M1(11,44); M2(74,92) = M1(11,45); M2(74,95) = M1(11,46); M2(74,96) = M1(11,47); M2(74,98) = M1(11,48); M2(74,101) = M1(11,49); M2(74,102) = M1(11,50); M2(74,103) = M1(11,51); M2(74,104) = M1(11,52); M2(74,105) = M1(11,53); M2(74,107) = M1(11,54); M2(74,108) = M1(11,55); M2(74,109) = M1(11,56); M2(74,110) = M1(11,57); M2(74,112) = M1(11,58); M2(74,113) = M1(11,59); M2(74,114) = M1(11,60); M2(74,116) = M1(11,61); M2(74,117) = M1(11,62); M2(74,119) = M1(11,63); M2(74,122) = M1(11,64); M2(74,123) = M1(11,65); M2(74,124) = M1(11,66); M2(74,125) = M1(11,67); M2(74,127) = M1(11,68); M2(74,128) = M1(11,69); M2(74,129) = M1(11,70); M2(74,131) = M1(11,71); M2(74,132) = M1(11,72); M2(74,134) = M1(11,73); M2(74,137) = M1(11,74); M2(74,138) = M1(11,75); M2(74,139) = M1(11,76); M2(74,141) = M1(11,77); M2(74,142) = M1(11,78); M2(74,144) = M1(11,79); M2(74,147) = M1(11,80); M2(74,148) = M1(11,81); M2(74,150) = M1(11,82); M2(74,153) = M1(11,83); M2(75,50) = M1(12,12); M2(75,54) = M1(12,15); M2(75,55) = M1(12,16); M2(75,56) = M1(12,17); M2(75,58) = M1(12,18); M2(75,59) = M1(12,19); M2(75,60) = M1(12,20); M2(75,61) = M1(12,21); M2(75,63) = M1(12,22); M2(75,64) = M1(12,23); M2(75,65) = M1(12,24); M2(75,67) = M1(12,25); M2(75,68) = M1(12,26); M2(75,70) = M1(12,27); M2(75,72) = M1(12,28); M2(75,73) = M1(12,29); M2(75,74) = M1(12,30); M2(75,75) = M1(12,31); M2(75,76) = M1(12,32); M2(75,77) = M1(12,33); M2(75,79) = M1(12,34); M2(75,80) = M1(12,35); M2(75,81) = M1(12,36); M2(75,82) = M1(12,37); M2(75,83) = M1(12,38); M2(75,85) = M1(12,39); M2(75,86) = M1(12,40); M2(75,87) = M1(12,41); M2(75,88) = M1(12,42); M2(75,90) = M1(12,43); M2(75,91) = M1(12,44); M2(75,92) = M1(12,45); M2(75,95) = M1(12,46); M2(75,96) = M1(12,47); M2(75,98) = M1(12,48); M2(75,101) = M1(12,49); M2(75,102) = M1(12,50); M2(75,103) = M1(12,51); M2(75,104) = M1(12,52); M2(75,105) = M1(12,53); M2(75,107) = M1(12,54); M2(75,108) = M1(12,55); M2(75,109) = M1(12,56); M2(75,110) = M1(12,57); M2(75,112) = M1(12,58); M2(75,113) = M1(12,59); M2(75,114) = M1(12,60); M2(75,116) = M1(12,61); M2(75,117) = M1(12,62); M2(75,119) = M1(12,63); M2(75,122) = M1(12,64); M2(75,123) = M1(12,65); M2(75,124) = M1(12,66); M2(75,125) = M1(12,67); M2(75,127) = M1(12,68); M2(75,128) = M1(12,69); M2(75,129) = M1(12,70); M2(75,131) = M1(12,71); M2(75,132) = M1(12,72); M2(75,134) = M1(12,73); M2(75,137) = M1(12,74); M2(75,138) = M1(12,75); M2(75,139) = M1(12,76); M2(75,141) = M1(12,77); M2(75,142) = M1(12,78); M2(75,144) = M1(12,79); M2(75,147) = M1(12,80); M2(75,148) = M1(12,81); M2(75,150) = M1(12,82); M2(75,153) = M1(12,83); M2(76,52) = M1(13,13); M2(76,54) = M1(13,15); M2(76,55) = M1(13,16); M2(76,56) = M1(13,17); M2(76,58) = M1(13,18); M2(76,59) = M1(13,19); M2(76,60) = M1(13,20); M2(76,61) = M1(13,21); M2(76,63) = M1(13,22); M2(76,64) = M1(13,23); M2(76,65) = M1(13,24); M2(76,67) = M1(13,25); M2(76,68) = M1(13,26); M2(76,70) = M1(13,27); M2(76,72) = M1(13,28); M2(76,73) = M1(13,29); M2(76,74) = M1(13,30); M2(76,75) = M1(13,31); M2(76,76) = M1(13,32); M2(76,77) = M1(13,33); M2(76,79) = M1(13,34); M2(76,80) = M1(13,35); M2(76,81) = M1(13,36); M2(76,82) = M1(13,37); M2(76,83) = M1(13,38); M2(76,85) = M1(13,39); M2(76,86) = M1(13,40); M2(76,87) = M1(13,41); M2(76,88) = M1(13,42); M2(76,90) = M1(13,43); M2(76,91) = M1(13,44); M2(76,92) = M1(13,45); M2(76,95) = M1(13,46); M2(76,96) = M1(13,47); M2(76,98) = M1(13,48); M2(76,101) = M1(13,49); M2(76,102) = M1(13,50); M2(76,103) = M1(13,51); M2(76,104) = M1(13,52); M2(76,105) = M1(13,53); M2(76,107) = M1(13,54); M2(76,108) = M1(13,55); M2(76,109) = M1(13,56); M2(76,110) = M1(13,57); M2(76,112) = M1(13,58); M2(76,113) = M1(13,59); M2(76,114) = M1(13,60); M2(76,116) = M1(13,61); M2(76,117) = M1(13,62); M2(76,119) = M1(13,63); M2(76,122) = M1(13,64); M2(76,123) = M1(13,65); M2(76,124) = M1(13,66); M2(76,125) = M1(13,67); M2(76,127) = M1(13,68); M2(76,128) = M1(13,69); M2(76,129) = M1(13,70); M2(76,131) = M1(13,71); M2(76,132) = M1(13,72); M2(76,134) = M1(13,73); M2(76,137) = M1(13,74); M2(76,138) = M1(13,75); M2(76,139) = M1(13,76); M2(76,141) = M1(13,77); M2(76,142) = M1(13,78); M2(76,144) = M1(13,79); M2(76,147) = M1(13,80); M2(76,148) = M1(13,81); M2(76,150) = M1(13,82); M2(76,153) = M1(13,83); M2(77,53) = M1(14,14); M2(77,54) = M1(14,15); M2(77,55) = M1(14,16); M2(77,56) = M1(14,17); M2(77,58) = M1(14,18); M2(77,59) = M1(14,19); M2(77,60) = M1(14,20); M2(77,61) = M1(14,21); M2(77,63) = M1(14,22); M2(77,64) = M1(14,23); M2(77,65) = M1(14,24); M2(77,67) = M1(14,25); M2(77,68) = M1(14,26); M2(77,70) = M1(14,27); M2(77,72) = M1(14,28); M2(77,73) = M1(14,29); M2(77,74) = M1(14,30); M2(77,75) = M1(14,31); M2(77,76) = M1(14,32); M2(77,77) = M1(14,33); M2(77,79) = M1(14,34); M2(77,80) = M1(14,35); M2(77,81) = M1(14,36); M2(77,82) = M1(14,37); M2(77,83) = M1(14,38); M2(77,85) = M1(14,39); M2(77,86) = M1(14,40); M2(77,87) = M1(14,41); M2(77,88) = M1(14,42); M2(77,90) = M1(14,43); M2(77,91) = M1(14,44); M2(77,92) = M1(14,45); M2(77,95) = M1(14,46); M2(77,96) = M1(14,47); M2(77,98) = M1(14,48); M2(77,101) = M1(14,49); M2(77,102) = M1(14,50); M2(77,103) = M1(14,51); M2(77,104) = M1(14,52); M2(77,105) = M1(14,53); M2(77,107) = M1(14,54); M2(77,108) = M1(14,55); M2(77,109) = M1(14,56); M2(77,110) = M1(14,57); M2(77,112) = M1(14,58); M2(77,113) = M1(14,59); M2(77,114) = M1(14,60); M2(77,116) = M1(14,61); M2(77,117) = M1(14,62); M2(77,119) = M1(14,63); M2(77,122) = M1(14,64); M2(77,123) = M1(14,65); M2(77,124) = M1(14,66); M2(77,125) = M1(14,67); M2(77,127) = M1(14,68); M2(77,128) = M1(14,69); M2(77,129) = M1(14,70); M2(77,131) = M1(14,71); M2(77,132) = M1(14,72); M2(77,134) = M1(14,73); M2(77,137) = M1(14,74); M2(77,138) = M1(14,75); M2(77,139) = M1(14,76); M2(77,141) = M1(14,77); M2(77,142) = M1(14,78); M2(77,144) = M1(14,79); M2(77,147) = M1(14,80); M2(77,148) = M1(14,81); M2(77,150) = M1(14,82); M2(77,153) = M1(14,83); M2(78,72) = M1(0,0); M2(78,87) = M1(0,15); M2(78,88) = M1(0,16); M2(78,89) = M1(0,17); M2(78,90) = M1(0,18); M2(78,91) = M1(0,19); M2(78,92) = M1(0,20); M2(78,94) = M1(0,21); M2(78,95) = M1(0,22); M2(78,96) = M1(0,23); M2(78,97) = M1(0,24); M2(78,98) = M1(0,25); M2(78,99) = M1(0,26); M2(78,100) = M1(0,27); M2(78,101) = M1(0,28); M2(78,102) = M1(0,29); M2(78,103) = M1(0,30); M2(78,104) = M1(0,31); M2(78,105) = M1(0,32); M2(78,106) = M1(0,33); M2(78,107) = M1(0,34); M2(78,108) = M1(0,35); M2(78,109) = M1(0,36); M2(78,110) = M1(0,37); M2(78,111) = M1(0,38); M2(78,112) = M1(0,39); M2(78,113) = M1(0,40); M2(78,114) = M1(0,41); M2(78,115) = M1(0,42); M2(78,116) = M1(0,43); M2(78,117) = M1(0,44); M2(78,118) = M1(0,45); M2(78,119) = M1(0,46); M2(78,120) = M1(0,47); M2(78,121) = M1(0,48); M2(78,122) = M1(0,49); M2(78,123) = M1(0,50); M2(78,124) = M1(0,51); M2(78,125) = M1(0,52); M2(78,126) = M1(0,53); M2(78,127) = M1(0,54); M2(78,128) = M1(0,55); M2(78,129) = M1(0,56); M2(78,130) = M1(0,57); M2(78,131) = M1(0,58); M2(78,132) = M1(0,59); M2(78,133) = M1(0,60); M2(78,134) = M1(0,61); M2(78,135) = M1(0,62); M2(78,136) = M1(0,63); M2(78,137) = M1(0,64); M2(78,138) = M1(0,65); M2(78,139) = M1(0,66); M2(78,140) = M1(0,67); M2(78,141) = M1(0,68); M2(78,142) = M1(0,69); M2(78,143) = M1(0,70); M2(78,144) = M1(0,71); M2(78,145) = M1(0,72); M2(78,146) = M1(0,73); M2(78,147) = M1(0,74); M2(78,148) = M1(0,75); M2(78,149) = M1(0,76); M2(78,150) = M1(0,77); M2(78,151) = M1(0,78); M2(78,152) = M1(0,79); M2(78,153) = M1(0,80); M2(78,154) = M1(0,81); M2(78,155) = M1(0,82); M2(78,156) = M1(0,83); M2(79,73) = M1(1,1); M2(79,87) = M1(1,15); M2(79,88) = M1(1,16); M2(79,89) = M1(1,17); M2(79,90) = M1(1,18); M2(79,91) = M1(1,19); M2(79,92) = M1(1,20); M2(79,94) = M1(1,21); M2(79,95) = M1(1,22); M2(79,96) = M1(1,23); M2(79,97) = M1(1,24); M2(79,98) = M1(1,25); M2(79,99) = M1(1,26); M2(79,100) = M1(1,27); M2(79,101) = M1(1,28); M2(79,102) = M1(1,29); M2(79,103) = M1(1,30); M2(79,104) = M1(1,31); M2(79,105) = M1(1,32); M2(79,106) = M1(1,33); M2(79,107) = M1(1,34); M2(79,108) = M1(1,35); M2(79,109) = M1(1,36); M2(79,110) = M1(1,37); M2(79,111) = M1(1,38); M2(79,112) = M1(1,39); M2(79,113) = M1(1,40); M2(79,114) = M1(1,41); M2(79,115) = M1(1,42); M2(79,116) = M1(1,43); M2(79,117) = M1(1,44); M2(79,118) = M1(1,45); M2(79,119) = M1(1,46); M2(79,120) = M1(1,47); M2(79,121) = M1(1,48); M2(79,122) = M1(1,49); M2(79,123) = M1(1,50); M2(79,124) = M1(1,51); M2(79,125) = M1(1,52); M2(79,126) = M1(1,53); M2(79,127) = M1(1,54); M2(79,128) = M1(1,55); M2(79,129) = M1(1,56); M2(79,130) = M1(1,57); M2(79,131) = M1(1,58); M2(79,132) = M1(1,59); M2(79,133) = M1(1,60); M2(79,134) = M1(1,61); M2(79,135) = M1(1,62); M2(79,136) = M1(1,63); M2(79,137) = M1(1,64); M2(79,138) = M1(1,65); M2(79,139) = M1(1,66); M2(79,140) = M1(1,67); M2(79,141) = M1(1,68); M2(79,142) = M1(1,69); M2(79,143) = M1(1,70); M2(79,144) = M1(1,71); M2(79,145) = M1(1,72); M2(79,146) = M1(1,73); M2(79,147) = M1(1,74); M2(79,148) = M1(1,75); M2(79,149) = M1(1,76); M2(79,150) = M1(1,77); M2(79,151) = M1(1,78); M2(79,152) = M1(1,79); M2(79,153) = M1(1,80); M2(79,154) = M1(1,81); M2(79,155) = M1(1,82); M2(79,156) = M1(1,83); M2(80,74) = M1(2,2); M2(80,87) = M1(2,15); M2(80,88) = M1(2,16); M2(80,89) = M1(2,17); M2(80,90) = M1(2,18); M2(80,91) = M1(2,19); M2(80,92) = M1(2,20); M2(80,94) = M1(2,21); M2(80,95) = M1(2,22); M2(80,96) = M1(2,23); M2(80,97) = M1(2,24); M2(80,98) = M1(2,25); M2(80,99) = M1(2,26); M2(80,100) = M1(2,27); M2(80,101) = M1(2,28); M2(80,102) = M1(2,29); M2(80,103) = M1(2,30); M2(80,104) = M1(2,31); M2(80,105) = M1(2,32); M2(80,106) = M1(2,33); M2(80,107) = M1(2,34); M2(80,108) = M1(2,35); M2(80,109) = M1(2,36); M2(80,110) = M1(2,37); M2(80,111) = M1(2,38); M2(80,112) = M1(2,39); M2(80,113) = M1(2,40); M2(80,114) = M1(2,41); M2(80,115) = M1(2,42); M2(80,116) = M1(2,43); M2(80,117) = M1(2,44); M2(80,118) = M1(2,45); M2(80,119) = M1(2,46); M2(80,120) = M1(2,47); M2(80,121) = M1(2,48); M2(80,122) = M1(2,49); M2(80,123) = M1(2,50); M2(80,124) = M1(2,51); M2(80,125) = M1(2,52); M2(80,126) = M1(2,53); M2(80,127) = M1(2,54); M2(80,128) = M1(2,55); M2(80,129) = M1(2,56); M2(80,130) = M1(2,57); M2(80,131) = M1(2,58); M2(80,132) = M1(2,59); M2(80,133) = M1(2,60); M2(80,134) = M1(2,61); M2(80,135) = M1(2,62); M2(80,136) = M1(2,63); M2(80,137) = M1(2,64); M2(80,138) = M1(2,65); M2(80,139) = M1(2,66); M2(80,140) = M1(2,67); M2(80,141) = M1(2,68); M2(80,142) = M1(2,69); M2(80,143) = M1(2,70); M2(80,144) = M1(2,71); M2(80,145) = M1(2,72); M2(80,146) = M1(2,73); M2(80,147) = M1(2,74); M2(80,148) = M1(2,75); M2(80,149) = M1(2,76); M2(80,150) = M1(2,77); M2(80,151) = M1(2,78); M2(80,152) = M1(2,79); M2(80,153) = M1(2,80); M2(80,154) = M1(2,81); M2(80,155) = M1(2,82); M2(80,156) = M1(2,83); M2(81,75) = M1(3,3); M2(81,87) = M1(3,15); M2(81,88) = M1(3,16); M2(81,89) = M1(3,17); M2(81,90) = M1(3,18); M2(81,91) = M1(3,19); M2(81,92) = M1(3,20); M2(81,94) = M1(3,21); M2(81,95) = M1(3,22); M2(81,96) = M1(3,23); M2(81,97) = M1(3,24); M2(81,98) = M1(3,25); M2(81,99) = M1(3,26); M2(81,100) = M1(3,27); M2(81,101) = M1(3,28); M2(81,102) = M1(3,29); M2(81,103) = M1(3,30); M2(81,104) = M1(3,31); M2(81,105) = M1(3,32); M2(81,106) = M1(3,33); M2(81,107) = M1(3,34); M2(81,108) = M1(3,35); M2(81,109) = M1(3,36); M2(81,110) = M1(3,37); M2(81,111) = M1(3,38); M2(81,112) = M1(3,39); M2(81,113) = M1(3,40); M2(81,114) = M1(3,41); M2(81,115) = M1(3,42); M2(81,116) = M1(3,43); M2(81,117) = M1(3,44); M2(81,118) = M1(3,45); M2(81,119) = M1(3,46); M2(81,120) = M1(3,47); M2(81,121) = M1(3,48); M2(81,122) = M1(3,49); M2(81,123) = M1(3,50); M2(81,124) = M1(3,51); M2(81,125) = M1(3,52); M2(81,126) = M1(3,53); M2(81,127) = M1(3,54); M2(81,128) = M1(3,55); M2(81,129) = M1(3,56); M2(81,130) = M1(3,57); M2(81,131) = M1(3,58); M2(81,132) = M1(3,59); M2(81,133) = M1(3,60); M2(81,134) = M1(3,61); M2(81,135) = M1(3,62); M2(81,136) = M1(3,63); M2(81,137) = M1(3,64); M2(81,138) = M1(3,65); M2(81,139) = M1(3,66); M2(81,140) = M1(3,67); M2(81,141) = M1(3,68); M2(81,142) = M1(3,69); M2(81,143) = M1(3,70); M2(81,144) = M1(3,71); M2(81,145) = M1(3,72); M2(81,146) = M1(3,73); M2(81,147) = M1(3,74); M2(81,148) = M1(3,75); M2(81,149) = M1(3,76); M2(81,150) = M1(3,77); M2(81,151) = M1(3,78); M2(81,152) = M1(3,79); M2(81,153) = M1(3,80); M2(81,154) = M1(3,81); M2(81,155) = M1(3,82); M2(81,156) = M1(3,83); M2(82,76) = M1(4,4); M2(82,87) = M1(4,15); M2(82,88) = M1(4,16); M2(82,89) = M1(4,17); M2(82,90) = M1(4,18); M2(82,91) = M1(4,19); M2(82,92) = M1(4,20); M2(82,94) = M1(4,21); M2(82,95) = M1(4,22); M2(82,96) = M1(4,23); M2(82,97) = M1(4,24); M2(82,98) = M1(4,25); M2(82,99) = M1(4,26); M2(82,100) = M1(4,27); M2(82,101) = M1(4,28); M2(82,102) = M1(4,29); M2(82,103) = M1(4,30); M2(82,104) = M1(4,31); M2(82,105) = M1(4,32); M2(82,106) = M1(4,33); M2(82,107) = M1(4,34); M2(82,108) = M1(4,35); M2(82,109) = M1(4,36); M2(82,110) = M1(4,37); M2(82,111) = M1(4,38); M2(82,112) = M1(4,39); M2(82,113) = M1(4,40); M2(82,114) = M1(4,41); M2(82,115) = M1(4,42); M2(82,116) = M1(4,43); M2(82,117) = M1(4,44); M2(82,118) = M1(4,45); M2(82,119) = M1(4,46); M2(82,120) = M1(4,47); M2(82,121) = M1(4,48); M2(82,122) = M1(4,49); M2(82,123) = M1(4,50); M2(82,124) = M1(4,51); M2(82,125) = M1(4,52); M2(82,126) = M1(4,53); M2(82,127) = M1(4,54); M2(82,128) = M1(4,55); M2(82,129) = M1(4,56); M2(82,130) = M1(4,57); M2(82,131) = M1(4,58); M2(82,132) = M1(4,59); M2(82,133) = M1(4,60); M2(82,134) = M1(4,61); M2(82,135) = M1(4,62); M2(82,136) = M1(4,63); M2(82,137) = M1(4,64); M2(82,138) = M1(4,65); M2(82,139) = M1(4,66); M2(82,140) = M1(4,67); M2(82,141) = M1(4,68); M2(82,142) = M1(4,69); M2(82,143) = M1(4,70); M2(82,144) = M1(4,71); M2(82,145) = M1(4,72); M2(82,146) = M1(4,73); M2(82,147) = M1(4,74); M2(82,148) = M1(4,75); M2(82,149) = M1(4,76); M2(82,150) = M1(4,77); M2(82,151) = M1(4,78); M2(82,152) = M1(4,79); M2(82,153) = M1(4,80); M2(82,154) = M1(4,81); M2(82,155) = M1(4,82); M2(82,156) = M1(4,83); M2(83,77) = M1(5,5); M2(83,87) = M1(5,15); M2(83,88) = M1(5,16); M2(83,89) = M1(5,17); M2(83,90) = M1(5,18); M2(83,91) = M1(5,19); M2(83,92) = M1(5,20); M2(83,94) = M1(5,21); M2(83,95) = M1(5,22); M2(83,96) = M1(5,23); M2(83,97) = M1(5,24); M2(83,98) = M1(5,25); M2(83,99) = M1(5,26); M2(83,100) = M1(5,27); M2(83,101) = M1(5,28); M2(83,102) = M1(5,29); M2(83,103) = M1(5,30); M2(83,104) = M1(5,31); M2(83,105) = M1(5,32); M2(83,106) = M1(5,33); M2(83,107) = M1(5,34); M2(83,108) = M1(5,35); M2(83,109) = M1(5,36); M2(83,110) = M1(5,37); M2(83,111) = M1(5,38); M2(83,112) = M1(5,39); M2(83,113) = M1(5,40); M2(83,114) = M1(5,41); M2(83,115) = M1(5,42); M2(83,116) = M1(5,43); M2(83,117) = M1(5,44); M2(83,118) = M1(5,45); M2(83,119) = M1(5,46); M2(83,120) = M1(5,47); M2(83,121) = M1(5,48); M2(83,122) = M1(5,49); M2(83,123) = M1(5,50); M2(83,124) = M1(5,51); M2(83,125) = M1(5,52); M2(83,126) = M1(5,53); M2(83,127) = M1(5,54); M2(83,128) = M1(5,55); M2(83,129) = M1(5,56); M2(83,130) = M1(5,57); M2(83,131) = M1(5,58); M2(83,132) = M1(5,59); M2(83,133) = M1(5,60); M2(83,134) = M1(5,61); M2(83,135) = M1(5,62); M2(83,136) = M1(5,63); M2(83,137) = M1(5,64); M2(83,138) = M1(5,65); M2(83,139) = M1(5,66); M2(83,140) = M1(5,67); M2(83,141) = M1(5,68); M2(83,142) = M1(5,69); M2(83,143) = M1(5,70); M2(83,144) = M1(5,71); M2(83,145) = M1(5,72); M2(83,146) = M1(5,73); M2(83,147) = M1(5,74); M2(83,148) = M1(5,75); M2(83,149) = M1(5,76); M2(83,150) = M1(5,77); M2(83,151) = M1(5,78); M2(83,152) = M1(5,79); M2(83,153) = M1(5,80); M2(83,154) = M1(5,81); M2(83,155) = M1(5,82); M2(83,156) = M1(5,83); M2(84,78) = M1(6,6); M2(84,87) = M1(6,15); M2(84,88) = M1(6,16); M2(84,89) = M1(6,17); M2(84,90) = M1(6,18); M2(84,91) = M1(6,19); M2(84,92) = M1(6,20); M2(84,94) = M1(6,21); M2(84,95) = M1(6,22); M2(84,96) = M1(6,23); M2(84,97) = M1(6,24); M2(84,98) = M1(6,25); M2(84,99) = M1(6,26); M2(84,100) = M1(6,27); M2(84,101) = M1(6,28); M2(84,102) = M1(6,29); M2(84,103) = M1(6,30); M2(84,104) = M1(6,31); M2(84,105) = M1(6,32); M2(84,106) = M1(6,33); M2(84,107) = M1(6,34); M2(84,108) = M1(6,35); M2(84,109) = M1(6,36); M2(84,110) = M1(6,37); M2(84,111) = M1(6,38); M2(84,112) = M1(6,39); M2(84,113) = M1(6,40); M2(84,114) = M1(6,41); M2(84,115) = M1(6,42); M2(84,116) = M1(6,43); M2(84,117) = M1(6,44); M2(84,118) = M1(6,45); M2(84,119) = M1(6,46); M2(84,120) = M1(6,47); M2(84,121) = M1(6,48); M2(84,122) = M1(6,49); M2(84,123) = M1(6,50); M2(84,124) = M1(6,51); M2(84,125) = M1(6,52); M2(84,126) = M1(6,53); M2(84,127) = M1(6,54); M2(84,128) = M1(6,55); M2(84,129) = M1(6,56); M2(84,130) = M1(6,57); M2(84,131) = M1(6,58); M2(84,132) = M1(6,59); M2(84,133) = M1(6,60); M2(84,134) = M1(6,61); M2(84,135) = M1(6,62); M2(84,136) = M1(6,63); M2(84,137) = M1(6,64); M2(84,138) = M1(6,65); M2(84,139) = M1(6,66); M2(84,140) = M1(6,67); M2(84,141) = M1(6,68); M2(84,142) = M1(6,69); M2(84,143) = M1(6,70); M2(84,144) = M1(6,71); M2(84,145) = M1(6,72); M2(84,146) = M1(6,73); M2(84,147) = M1(6,74); M2(84,148) = M1(6,75); M2(84,149) = M1(6,76); M2(84,150) = M1(6,77); M2(84,151) = M1(6,78); M2(84,152) = M1(6,79); M2(84,153) = M1(6,80); M2(84,154) = M1(6,81); M2(84,155) = M1(6,82); M2(84,156) = M1(6,83); M2(85,79) = M1(7,7); M2(85,87) = M1(7,15); M2(85,88) = M1(7,16); M2(85,89) = M1(7,17); M2(85,90) = M1(7,18); M2(85,91) = M1(7,19); M2(85,92) = M1(7,20); M2(85,94) = M1(7,21); M2(85,95) = M1(7,22); M2(85,96) = M1(7,23); M2(85,97) = M1(7,24); M2(85,98) = M1(7,25); M2(85,99) = M1(7,26); M2(85,100) = M1(7,27); M2(85,101) = M1(7,28); M2(85,102) = M1(7,29); M2(85,103) = M1(7,30); M2(85,104) = M1(7,31); M2(85,105) = M1(7,32); M2(85,106) = M1(7,33); M2(85,107) = M1(7,34); M2(85,108) = M1(7,35); M2(85,109) = M1(7,36); M2(85,110) = M1(7,37); M2(85,111) = M1(7,38); M2(85,112) = M1(7,39); M2(85,113) = M1(7,40); M2(85,114) = M1(7,41); M2(85,115) = M1(7,42); M2(85,116) = M1(7,43); M2(85,117) = M1(7,44); M2(85,118) = M1(7,45); M2(85,119) = M1(7,46); M2(85,120) = M1(7,47); M2(85,121) = M1(7,48); M2(85,122) = M1(7,49); M2(85,123) = M1(7,50); M2(85,124) = M1(7,51); M2(85,125) = M1(7,52); M2(85,126) = M1(7,53); M2(85,127) = M1(7,54); M2(85,128) = M1(7,55); M2(85,129) = M1(7,56); M2(85,130) = M1(7,57); M2(85,131) = M1(7,58); M2(85,132) = M1(7,59); M2(85,133) = M1(7,60); M2(85,134) = M1(7,61); M2(85,135) = M1(7,62); M2(85,136) = M1(7,63); M2(85,137) = M1(7,64); M2(85,138) = M1(7,65); M2(85,139) = M1(7,66); M2(85,140) = M1(7,67); M2(85,141) = M1(7,68); M2(85,142) = M1(7,69); M2(85,143) = M1(7,70); M2(85,144) = M1(7,71); M2(85,145) = M1(7,72); M2(85,146) = M1(7,73); M2(85,147) = M1(7,74); M2(85,148) = M1(7,75); M2(85,149) = M1(7,76); M2(85,150) = M1(7,77); M2(85,151) = M1(7,78); M2(85,152) = M1(7,79); M2(85,153) = M1(7,80); M2(85,154) = M1(7,81); M2(85,155) = M1(7,82); M2(85,156) = M1(7,83); M2(86,80) = M1(8,8); M2(86,87) = M1(8,15); M2(86,88) = M1(8,16); M2(86,89) = M1(8,17); M2(86,90) = M1(8,18); M2(86,91) = M1(8,19); M2(86,92) = M1(8,20); M2(86,94) = M1(8,21); M2(86,95) = M1(8,22); M2(86,96) = M1(8,23); M2(86,97) = M1(8,24); M2(86,98) = M1(8,25); M2(86,99) = M1(8,26); M2(86,100) = M1(8,27); M2(86,101) = M1(8,28); M2(86,102) = M1(8,29); M2(86,103) = M1(8,30); M2(86,104) = M1(8,31); M2(86,105) = M1(8,32); M2(86,106) = M1(8,33); M2(86,107) = M1(8,34); M2(86,108) = M1(8,35); M2(86,109) = M1(8,36); M2(86,110) = M1(8,37); M2(86,111) = M1(8,38); M2(86,112) = M1(8,39); M2(86,113) = M1(8,40); M2(86,114) = M1(8,41); M2(86,115) = M1(8,42); M2(86,116) = M1(8,43); M2(86,117) = M1(8,44); M2(86,118) = M1(8,45); M2(86,119) = M1(8,46); M2(86,120) = M1(8,47); M2(86,121) = M1(8,48); M2(86,122) = M1(8,49); M2(86,123) = M1(8,50); M2(86,124) = M1(8,51); M2(86,125) = M1(8,52); M2(86,126) = M1(8,53); M2(86,127) = M1(8,54); M2(86,128) = M1(8,55); M2(86,129) = M1(8,56); M2(86,130) = M1(8,57); M2(86,131) = M1(8,58); M2(86,132) = M1(8,59); M2(86,133) = M1(8,60); M2(86,134) = M1(8,61); M2(86,135) = M1(8,62); M2(86,136) = M1(8,63); M2(86,137) = M1(8,64); M2(86,138) = M1(8,65); M2(86,139) = M1(8,66); M2(86,140) = M1(8,67); M2(86,141) = M1(8,68); M2(86,142) = M1(8,69); M2(86,143) = M1(8,70); M2(86,144) = M1(8,71); M2(86,145) = M1(8,72); M2(86,146) = M1(8,73); M2(86,147) = M1(8,74); M2(86,148) = M1(8,75); M2(86,149) = M1(8,76); M2(86,150) = M1(8,77); M2(86,151) = M1(8,78); M2(86,152) = M1(8,79); M2(86,153) = M1(8,80); M2(86,154) = M1(8,81); M2(86,155) = M1(8,82); M2(86,156) = M1(8,83); M2(87,81) = M1(9,9); M2(87,87) = M1(9,15); M2(87,88) = M1(9,16); M2(87,89) = M1(9,17); M2(87,90) = M1(9,18); M2(87,91) = M1(9,19); M2(87,92) = M1(9,20); M2(87,94) = M1(9,21); M2(87,95) = M1(9,22); M2(87,96) = M1(9,23); M2(87,97) = M1(9,24); M2(87,98) = M1(9,25); M2(87,99) = M1(9,26); M2(87,100) = M1(9,27); M2(87,101) = M1(9,28); M2(87,102) = M1(9,29); M2(87,103) = M1(9,30); M2(87,104) = M1(9,31); M2(87,105) = M1(9,32); M2(87,106) = M1(9,33); M2(87,107) = M1(9,34); M2(87,108) = M1(9,35); M2(87,109) = M1(9,36); M2(87,110) = M1(9,37); M2(87,111) = M1(9,38); M2(87,112) = M1(9,39); M2(87,113) = M1(9,40); M2(87,114) = M1(9,41); M2(87,115) = M1(9,42); M2(87,116) = M1(9,43); M2(87,117) = M1(9,44); M2(87,118) = M1(9,45); M2(87,119) = M1(9,46); M2(87,120) = M1(9,47); M2(87,121) = M1(9,48); M2(87,122) = M1(9,49); M2(87,123) = M1(9,50); M2(87,124) = M1(9,51); M2(87,125) = M1(9,52); M2(87,126) = M1(9,53); M2(87,127) = M1(9,54); M2(87,128) = M1(9,55); M2(87,129) = M1(9,56); M2(87,130) = M1(9,57); M2(87,131) = M1(9,58); M2(87,132) = M1(9,59); M2(87,133) = M1(9,60); M2(87,134) = M1(9,61); M2(87,135) = M1(9,62); M2(87,136) = M1(9,63); M2(87,137) = M1(9,64); M2(87,138) = M1(9,65); M2(87,139) = M1(9,66); M2(87,140) = M1(9,67); M2(87,141) = M1(9,68); M2(87,142) = M1(9,69); M2(87,143) = M1(9,70); M2(87,144) = M1(9,71); M2(87,145) = M1(9,72); M2(87,146) = M1(9,73); M2(87,147) = M1(9,74); M2(87,148) = M1(9,75); M2(87,149) = M1(9,76); M2(87,150) = M1(9,77); M2(87,151) = M1(9,78); M2(87,152) = M1(9,79); M2(87,153) = M1(9,80); M2(87,154) = M1(9,81); M2(87,155) = M1(9,82); M2(87,156) = M1(9,83); M2(88,82) = M1(10,10); M2(88,87) = M1(10,15); M2(88,88) = M1(10,16); M2(88,89) = M1(10,17); M2(88,90) = M1(10,18); M2(88,91) = M1(10,19); M2(88,92) = M1(10,20); M2(88,94) = M1(10,21); M2(88,95) = M1(10,22); M2(88,96) = M1(10,23); M2(88,97) = M1(10,24); M2(88,98) = M1(10,25); M2(88,99) = M1(10,26); M2(88,100) = M1(10,27); M2(88,101) = M1(10,28); M2(88,102) = M1(10,29); M2(88,103) = M1(10,30); M2(88,104) = M1(10,31); M2(88,105) = M1(10,32); M2(88,106) = M1(10,33); M2(88,107) = M1(10,34); M2(88,108) = M1(10,35); M2(88,109) = M1(10,36); M2(88,110) = M1(10,37); M2(88,111) = M1(10,38); M2(88,112) = M1(10,39); M2(88,113) = M1(10,40); M2(88,114) = M1(10,41); M2(88,115) = M1(10,42); M2(88,116) = M1(10,43); M2(88,117) = M1(10,44); M2(88,118) = M1(10,45); M2(88,119) = M1(10,46); M2(88,120) = M1(10,47); M2(88,121) = M1(10,48); M2(88,122) = M1(10,49); M2(88,123) = M1(10,50); M2(88,124) = M1(10,51); M2(88,125) = M1(10,52); M2(88,126) = M1(10,53); M2(88,127) = M1(10,54); M2(88,128) = M1(10,55); M2(88,129) = M1(10,56); M2(88,130) = M1(10,57); M2(88,131) = M1(10,58); M2(88,132) = M1(10,59); M2(88,133) = M1(10,60); M2(88,134) = M1(10,61); M2(88,135) = M1(10,62); M2(88,136) = M1(10,63); M2(88,137) = M1(10,64); M2(88,138) = M1(10,65); M2(88,139) = M1(10,66); M2(88,140) = M1(10,67); M2(88,141) = M1(10,68); M2(88,142) = M1(10,69); M2(88,143) = M1(10,70); M2(88,144) = M1(10,71); M2(88,145) = M1(10,72); M2(88,146) = M1(10,73); M2(88,147) = M1(10,74); M2(88,148) = M1(10,75); M2(88,149) = M1(10,76); M2(88,150) = M1(10,77); M2(88,151) = M1(10,78); M2(88,152) = M1(10,79); M2(88,153) = M1(10,80); M2(88,154) = M1(10,81); M2(88,155) = M1(10,82); M2(88,156) = M1(10,83); M2(89,83) = M1(11,11); M2(89,87) = M1(11,15); M2(89,88) = M1(11,16); M2(89,89) = M1(11,17); M2(89,90) = M1(11,18); M2(89,91) = M1(11,19); M2(89,92) = M1(11,20); M2(89,94) = M1(11,21); M2(89,95) = M1(11,22); M2(89,96) = M1(11,23); M2(89,97) = M1(11,24); M2(89,98) = M1(11,25); M2(89,99) = M1(11,26); M2(89,100) = M1(11,27); M2(89,101) = M1(11,28); M2(89,102) = M1(11,29); M2(89,103) = M1(11,30); M2(89,104) = M1(11,31); M2(89,105) = M1(11,32); M2(89,106) = M1(11,33); M2(89,107) = M1(11,34); M2(89,108) = M1(11,35); M2(89,109) = M1(11,36); M2(89,110) = M1(11,37); M2(89,111) = M1(11,38); M2(89,112) = M1(11,39); M2(89,113) = M1(11,40); M2(89,114) = M1(11,41); M2(89,115) = M1(11,42); M2(89,116) = M1(11,43); M2(89,117) = M1(11,44); M2(89,118) = M1(11,45); M2(89,119) = M1(11,46); M2(89,120) = M1(11,47); M2(89,121) = M1(11,48); M2(89,122) = M1(11,49); M2(89,123) = M1(11,50); M2(89,124) = M1(11,51); M2(89,125) = M1(11,52); M2(89,126) = M1(11,53); M2(89,127) = M1(11,54); M2(89,128) = M1(11,55); M2(89,129) = M1(11,56); M2(89,130) = M1(11,57); M2(89,131) = M1(11,58); M2(89,132) = M1(11,59); M2(89,133) = M1(11,60); M2(89,134) = M1(11,61); M2(89,135) = M1(11,62); M2(89,136) = M1(11,63); M2(89,137) = M1(11,64); M2(89,138) = M1(11,65); M2(89,139) = M1(11,66); M2(89,140) = M1(11,67); M2(89,141) = M1(11,68); M2(89,142) = M1(11,69); M2(89,143) = M1(11,70); M2(89,144) = M1(11,71); M2(89,145) = M1(11,72); M2(89,146) = M1(11,73); M2(89,147) = M1(11,74); M2(89,148) = M1(11,75); M2(89,149) = M1(11,76); M2(89,150) = M1(11,77); M2(89,151) = M1(11,78); M2(89,152) = M1(11,79); M2(89,153) = M1(11,80); M2(89,154) = M1(11,81); M2(89,155) = M1(11,82); M2(89,156) = M1(11,83); M2(90,84) = M1(12,12); M2(90,87) = M1(12,15); M2(90,88) = M1(12,16); M2(90,89) = M1(12,17); M2(90,90) = M1(12,18); M2(90,91) = M1(12,19); M2(90,92) = M1(12,20); M2(90,94) = M1(12,21); M2(90,95) = M1(12,22); M2(90,96) = M1(12,23); M2(90,97) = M1(12,24); M2(90,98) = M1(12,25); M2(90,99) = M1(12,26); M2(90,100) = M1(12,27); M2(90,101) = M1(12,28); M2(90,102) = M1(12,29); M2(90,103) = M1(12,30); M2(90,104) = M1(12,31); M2(90,105) = M1(12,32); M2(90,106) = M1(12,33); M2(90,107) = M1(12,34); M2(90,108) = M1(12,35); M2(90,109) = M1(12,36); M2(90,110) = M1(12,37); M2(90,111) = M1(12,38); M2(90,112) = M1(12,39); M2(90,113) = M1(12,40); M2(90,114) = M1(12,41); M2(90,115) = M1(12,42); M2(90,116) = M1(12,43); M2(90,117) = M1(12,44); M2(90,118) = M1(12,45); M2(90,119) = M1(12,46); M2(90,120) = M1(12,47); M2(90,121) = M1(12,48); M2(90,122) = M1(12,49); M2(90,123) = M1(12,50); M2(90,124) = M1(12,51); M2(90,125) = M1(12,52); M2(90,126) = M1(12,53); M2(90,127) = M1(12,54); M2(90,128) = M1(12,55); M2(90,129) = M1(12,56); M2(90,130) = M1(12,57); M2(90,131) = M1(12,58); M2(90,132) = M1(12,59); M2(90,133) = M1(12,60); M2(90,134) = M1(12,61); M2(90,135) = M1(12,62); M2(90,136) = M1(12,63); M2(90,137) = M1(12,64); M2(90,138) = M1(12,65); M2(90,139) = M1(12,66); M2(90,140) = M1(12,67); M2(90,141) = M1(12,68); M2(90,142) = M1(12,69); M2(90,143) = M1(12,70); M2(90,144) = M1(12,71); M2(90,145) = M1(12,72); M2(90,146) = M1(12,73); M2(90,147) = M1(12,74); M2(90,148) = M1(12,75); M2(90,149) = M1(12,76); M2(90,150) = M1(12,77); M2(90,151) = M1(12,78); M2(90,152) = M1(12,79); M2(90,153) = M1(12,80); M2(90,154) = M1(12,81); M2(90,155) = M1(12,82); M2(90,156) = M1(12,83); M2(91,85) = M1(13,13); M2(91,87) = M1(13,15); M2(91,88) = M1(13,16); M2(91,89) = M1(13,17); M2(91,90) = M1(13,18); M2(91,91) = M1(13,19); M2(91,92) = M1(13,20); M2(91,94) = M1(13,21); M2(91,95) = M1(13,22); M2(91,96) = M1(13,23); M2(91,97) = M1(13,24); M2(91,98) = M1(13,25); M2(91,99) = M1(13,26); M2(91,100) = M1(13,27); M2(91,101) = M1(13,28); M2(91,102) = M1(13,29); M2(91,103) = M1(13,30); M2(91,104) = M1(13,31); M2(91,105) = M1(13,32); M2(91,106) = M1(13,33); M2(91,107) = M1(13,34); M2(91,108) = M1(13,35); M2(91,109) = M1(13,36); M2(91,110) = M1(13,37); M2(91,111) = M1(13,38); M2(91,112) = M1(13,39); M2(91,113) = M1(13,40); M2(91,114) = M1(13,41); M2(91,115) = M1(13,42); M2(91,116) = M1(13,43); M2(91,117) = M1(13,44); M2(91,118) = M1(13,45); M2(91,119) = M1(13,46); M2(91,120) = M1(13,47); M2(91,121) = M1(13,48); M2(91,122) = M1(13,49); M2(91,123) = M1(13,50); M2(91,124) = M1(13,51); M2(91,125) = M1(13,52); M2(91,126) = M1(13,53); M2(91,127) = M1(13,54); M2(91,128) = M1(13,55); M2(91,129) = M1(13,56); M2(91,130) = M1(13,57); M2(91,131) = M1(13,58); M2(91,132) = M1(13,59); M2(91,133) = M1(13,60); M2(91,134) = M1(13,61); M2(91,135) = M1(13,62); M2(91,136) = M1(13,63); M2(91,137) = M1(13,64); M2(91,138) = M1(13,65); M2(91,139) = M1(13,66); M2(91,140) = M1(13,67); M2(91,141) = M1(13,68); M2(91,142) = M1(13,69); M2(91,143) = M1(13,70); M2(91,144) = M1(13,71); M2(91,145) = M1(13,72); M2(91,146) = M1(13,73); M2(91,147) = M1(13,74); M2(91,148) = M1(13,75); M2(91,149) = M1(13,76); M2(91,150) = M1(13,77); M2(91,151) = M1(13,78); M2(91,152) = M1(13,79); M2(91,153) = M1(13,80); M2(91,154) = M1(13,81); M2(91,155) = M1(13,82); M2(91,156) = M1(13,83); M2(92,86) = M1(14,14); M2(92,87) = M1(14,15); M2(92,88) = M1(14,16); M2(92,89) = M1(14,17); M2(92,90) = M1(14,18); M2(92,91) = M1(14,19); M2(92,92) = M1(14,20); M2(92,94) = M1(14,21); M2(92,95) = M1(14,22); M2(92,96) = M1(14,23); M2(92,97) = M1(14,24); M2(92,98) = M1(14,25); M2(92,99) = M1(14,26); M2(92,100) = M1(14,27); M2(92,101) = M1(14,28); M2(92,102) = M1(14,29); M2(92,103) = M1(14,30); M2(92,104) = M1(14,31); M2(92,105) = M1(14,32); M2(92,106) = M1(14,33); M2(92,107) = M1(14,34); M2(92,108) = M1(14,35); M2(92,109) = M1(14,36); M2(92,110) = M1(14,37); M2(92,111) = M1(14,38); M2(92,112) = M1(14,39); M2(92,113) = M1(14,40); M2(92,114) = M1(14,41); M2(92,115) = M1(14,42); M2(92,116) = M1(14,43); M2(92,117) = M1(14,44); M2(92,118) = M1(14,45); M2(92,119) = M1(14,46); M2(92,120) = M1(14,47); M2(92,121) = M1(14,48); M2(92,122) = M1(14,49); M2(92,123) = M1(14,50); M2(92,124) = M1(14,51); M2(92,125) = M1(14,52); M2(92,126) = M1(14,53); M2(92,127) = M1(14,54); M2(92,128) = M1(14,55); M2(92,129) = M1(14,56); M2(92,130) = M1(14,57); M2(92,131) = M1(14,58); M2(92,132) = M1(14,59); M2(92,133) = M1(14,60); M2(92,134) = M1(14,61); M2(92,135) = M1(14,62); M2(92,136) = M1(14,63); M2(92,137) = M1(14,64); M2(92,138) = M1(14,65); M2(92,139) = M1(14,66); M2(92,140) = M1(14,67); M2(92,141) = M1(14,68); M2(92,142) = M1(14,69); M2(92,143) = M1(14,70); M2(92,144) = M1(14,71); M2(92,145) = M1(14,72); M2(92,146) = M1(14,73); M2(92,147) = M1(14,74); M2(92,148) = M1(14,75); M2(92,149) = M1(14,76); M2(92,150) = M1(14,77); M2(92,151) = M1(14,78); M2(92,152) = M1(14,79); M2(92,153) = M1(14,80); M2(92,154) = M1(14,81); M2(92,155) = M1(14,82); M2(92,156) = M1(14,83); Eigen::PartialPivLU< Eigen::Matrix > lu(M2.block<93,93>(0,0)); Eigen::Matrix M3 = lu.solve(M2.block<93,64>(0,93)); Action = Eigen::Matrix::Zero(); Action.row(0) -= M3.block<1,64>(36,0); Action.row(1) -= M3.block<1,64>(66,0); Action.row(2) -= M3.block<1,64>(67,0); Action.row(3) -= M3.block<1,64>(68,0); Action.row(4) -= M3.block<1,64>(69,0); Action.row(5) -= M3.block<1,64>(70,0); Action.row(6) -= M3.block<1,64>(71,0); Action(7,0) = 1.0; Action.row(8) -= M3.block<1,64>(79,0); Action.row(9) -= M3.block<1,64>(80,0); Action.row(10) -= M3.block<1,64>(81,0); Action.row(11) -= M3.block<1,64>(82,0); Action.row(12) -= M3.block<1,64>(83,0); Action.row(13) -= M3.block<1,64>(84,0); Action.row(14) -= M3.block<1,64>(85,0); Action.row(15) -= M3.block<1,64>(86,0); Action.row(16) -= M3.block<1,64>(87,0); Action.row(17) -= M3.block<1,64>(88,0); Action.row(18) -= M3.block<1,64>(89,0); Action.row(19) -= M3.block<1,64>(90,0); Action.row(20) -= M3.block<1,64>(91,0); Action.row(21) -= M3.block<1,64>(92,0); Action(22,1) = 1.0; Action(23,2) = 1.0; Action(24,3) = 1.0; Action(25,4) = 1.0; Action(26,5) = 1.0; Action(27,6) = 1.0; Action(28,7) = 1.0; Action(29,14) = 1.0; Action(30,15) = 1.0; Action(31,16) = 1.0; Action(32,17) = 1.0; Action(33,18) = 1.0; Action(34,19) = 1.0; Action(35,20) = 1.0; Action(36,21) = 1.0; Action(37,22) = 1.0; Action(38,23) = 1.0; Action(39,24) = 1.0; Action(40,25) = 1.0; Action(41,26) = 1.0; Action(42,27) = 1.0; Action(43,28) = 1.0; Action(44,34) = 1.0; Action(45,35) = 1.0; Action(46,36) = 1.0; Action(47,37) = 1.0; Action(48,38) = 1.0; Action(49,39) = 1.0; Action(50,40) = 1.0; Action(51,41) = 1.0; Action(52,42) = 1.0; Action(53,43) = 1.0; Action(54,48) = 1.0; Action(55,49) = 1.0; Action(56,50) = 1.0; Action(57,51) = 1.0; Action(58,52) = 1.0; Action(59,53) = 1.0; Action(60,57) = 1.0; Action(61,58) = 1.0; Action(62,59) = 1.0; Action(63,62) = 1.0; //columns of Action mean: // x_3^7 x_2^3*x_3^3 x_1^2*x_3^4 x_1*x_2*x_3^4 x_2^2*x_3^4 x_1*x_3^5 x_2*x_3^5 x_3^6 x_1^5 x_1^4*x_2 x_1^3*x_2^2 x_1^2*x_2^3 x_1*x_2^4 x_2^5 x_1^4*x_3 x_1^3*x_2*x_3 x_1^2*x_2^2*x_3 x_1*x_2^3*x_3 x_2^4*x_3 x_1^3*x_3^2 x_1^2*x_2*x_3^2 x_1*x_2^2*x_3^2 x_2^3*x_3^2 x_1^2*x_3^3 x_1*x_2*x_3^3 x_2^2*x_3^3 x_1*x_3^4 x_2*x_3^4 x_3^5 x_1^4 x_1^3*x_2 x_1^2*x_2^2 x_1*x_2^3 x_2^4 x_1^3*x_3 x_1^2*x_2*x_3 x_1*x_2^2*x_3 x_2^3*x_3 x_1^2*x_3^2 x_1*x_2*x_3^2 x_2^2*x_3^2 x_1*x_3^3 x_2*x_3^3 x_3^4 x_1^3 x_1^2*x_2 x_1*x_2^2 x_2^3 x_1^2*x_3 x_1*x_2*x_3 x_2^2*x_3 x_1*x_3^2 x_2*x_3^2 x_3^3 x_1^2 x_1*x_2 x_2^2 x_1*x_3 x_2*x_3 x_3^2 x_1 x_2 x_3 1 } opengv/src/relative_pose/modules/main.cpp0000644016516101651610000011234014257362435017544 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include void opengv::relative_pose::modules::fivept_stewenius_main( const Eigen::Matrix & EE, complexEssentials_t & complexEssentials ) { Eigen::Matrix A; fivept_stewenius::composeA(EE,A); Eigen::Matrix A1 = A.block(0,0,10,10); Eigen::Matrix A2 = A.block(0,10,10,10); Eigen::FullPivLU< Eigen::Matrix > luA1(A1); Eigen::Matrix A3 = luA1.inverse()*A2; Eigen::Matrix M; M.block(0,0,3,10) = -A3.block(0,0,3,10); M.block(3,0,2,10) = -A3.block(4,0,2,10); M.row(5) = -A3.row(7); M.block(6,0,4,10) = Eigen::Matrix::Zero(); M(6,0) = 1.0; M(7,1) = 1.0; M(8,3) = 1.0; M(9,6) = 1.0; Eigen::EigenSolver< Eigen::Matrix > Eig(M,true); //Eigen::Matrix,10,1> D = Eig.eigenvalues(); Eigen::Matrix,10,10> V = Eig.eigenvectors(); Eigen::Matrix,3,10> V1; V1 = V.block(6,0,3,10); Eigen::Matrix,3,10> V2; V2.row(0) = V.row(9); V2.row(1) = V.row(9); V2.row(2) = V.row(9); Eigen::Matrix,4,10> SOLS; for( int r = 0; r < 3; r++ ) { for( int c = 0; c < 10; c++ ) SOLS(r,c) = V1(r,c)/V2(r,c); } SOLS.row(3) = Eigen::Matrix,1,10>:: Constant(std::complex(1.0,0.0)); Eigen::Matrix,9,10> Evec = EE * SOLS; Eigen::Matrix,1,10> norms; for( int c = 0; c < 10; c++ ) { norms(0,c) = std::complex(0.0,0.0); for( int r = 0; r < 9; r++ ) norms(0,c) += pow( Evec(r,c), 2 ); norms(0,c) = sqrt(norms(0,c)); } Eigen::Matrix,9,10> EvecNorms; for( int i = 0; i < 9; i++ ) EvecNorms.row(i) = norms; for( int r = 0; r < 9; r++ ) { for( int c = 0; c < 10; c++ ) Evec(r,c) = Evec(r,c) / EvecNorms(r,c); } for( int c = 0; c < 10; c++ ) { complexEssential_t complexEssential; complexEssential.row(0) = Evec.block(0,c,3,1).transpose(); complexEssential.row(1) = Evec.block(3,c,3,1).transpose(); complexEssential.row(2) = Evec.block(6,c,3,1).transpose(); complexEssentials.push_back(complexEssential); } } void opengv::relative_pose::modules::fivept_nister_main( const Eigen::Matrix & EE, essentials_t & essentials ) { Eigen::Matrix A; fivept_nister::composeA(EE,A); Eigen::Matrix A1 = A.block(0,0,10,10); Eigen::Matrix A2 = A.block(0,10,10,10); Eigen::FullPivLU< Eigen::Matrix > luA1(A1); Eigen::Matrix A3 = luA1.inverse()*A2; Eigen::Matrix b11_part1 = Eigen::Matrix::Zero(); b11_part1.block<1,3>(0,1) = A3.block<1,3>(4,0); Eigen::Matrix b11_part2 = Eigen::Matrix::Zero(); b11_part2.block<1,3>(0,0) = A3.block<1,3>(5,0); Eigen::Matrix b11 = b11_part1 - b11_part2; Eigen::Matrix b21_part1 = Eigen::Matrix::Zero(); b21_part1.block<1,3>(0,1) = A3.block<1,3>(6,0); Eigen::Matrix b21_part2 = Eigen::Matrix::Zero(); b21_part2.block<1,3>(0,0) = A3.block<1,3>(7,0); Eigen::Matrix b21 = b21_part1 - b21_part2; Eigen::Matrix b31_part1 = Eigen::Matrix::Zero(); b31_part1.block<1,3>(0,1) = A3.block<1,3>(8,0); Eigen::Matrix b31_part2 = Eigen::Matrix::Zero(); b31_part2.block<1,3>(0,0) = A3.block<1,3>(9,0); Eigen::Matrix b31 = b31_part1 - b31_part2; Eigen::Matrix b12_part1 = Eigen::Matrix::Zero(); b12_part1.block<1,3>(0,1) = A3.block<1,3>(4,3); Eigen::Matrix b12_part2 = Eigen::Matrix::Zero(); b12_part2.block<1,3>(0,0) = A3.block<1,3>(5,3); Eigen::Matrix b12 = b12_part1 - b12_part2; Eigen::Matrix b22_part1 = Eigen::Matrix::Zero(); b22_part1.block<1,3>(0,1) = A3.block<1,3>(6,3); Eigen::Matrix b22_part2 = Eigen::Matrix::Zero(); b22_part2.block<1,3>(0,0) = A3.block<1,3>(7,3); Eigen::Matrix b22 = b22_part1 - b22_part2; Eigen::Matrix b32_part1 = Eigen::Matrix::Zero(); b32_part1.block<1,3>(0,1) = A3.block<1,3>(8,3); Eigen::Matrix b32_part2 = Eigen::Matrix::Zero(); b32_part2.block<1,3>(0,0) = A3.block<1,3>(9,3); Eigen::Matrix b32 = b32_part1 - b32_part2; Eigen::Matrix b13_part1 = Eigen::Matrix::Zero(); b13_part1.block<1,4>(0,1) = A3.block<1,4>(4,6); Eigen::Matrix b13_part2 = Eigen::Matrix::Zero(); b13_part2.block<1,4>(0,0) = A3.block<1,4>(5,6); Eigen::Matrix b13 = b13_part1 - b13_part2; Eigen::Matrix b23_part1 = Eigen::Matrix::Zero(); b23_part1.block<1,4>(0,1) = A3.block<1,4>(6,6); Eigen::Matrix b23_part2 = Eigen::Matrix::Zero(); b23_part2.block<1,4>(0,0) = A3.block<1,4>(7,6); Eigen::Matrix b23 = b23_part1 - b23_part2; Eigen::Matrix b33_part1 = Eigen::Matrix::Zero(); b33_part1.block<1,4>(0,1) = A3.block<1,4>(8,6); Eigen::Matrix b33_part2 = Eigen::Matrix::Zero(); b33_part2.block<1,4>(0,0) = A3.block<1,4>(9,6); Eigen::Matrix b33 = b33_part1 - b33_part2; Eigen::Matrix p1_part1; fivept_nister::computeSeventhOrderPolynomial(b23,b12,p1_part1); Eigen::Matrix p1_part2; fivept_nister::computeSeventhOrderPolynomial(b13,b22,p1_part2); Eigen::Matrix p1 = p1_part1 - p1_part2; Eigen::Matrix p2_part1; fivept_nister::computeSeventhOrderPolynomial(b13,b21,p2_part1); Eigen::Matrix p2_part2; fivept_nister::computeSeventhOrderPolynomial(b23,b11,p2_part2); Eigen::Matrix p2 = p2_part1 - p2_part2; Eigen::Matrix p3_part1; fivept_nister::computeSixthOrderPolynomial(b11,b22,p3_part1); Eigen::Matrix p3_part2; fivept_nister::computeSixthOrderPolynomial(b12,b21,p3_part2); Eigen::Matrix p3 = p3_part1 - p3_part2; Eigen::Matrix p_order10_part1; fivept_nister::computeTenthOrderPolynomialFrom73(p1,b31,p_order10_part1); Eigen::Matrix p_order10_part2; fivept_nister::computeTenthOrderPolynomialFrom73(p2,b32,p_order10_part2); Eigen::Matrix p_order10_part3; fivept_nister::computeTenthOrderPolynomialFrom64(p3,b33,p_order10_part3); Eigen::Matrix p_order10 = p_order10_part1 + p_order10_part2 + p_order10_part3; math::Sturm sturmSequence(p_order10); std::vector roots = sturmSequence.findRoots(); Eigen::MatrixXd Evec(9,roots.size()); for( size_t i = 0; i < roots.size(); i++ ) { double z = roots[i]; double x = fivept_nister::polyVal(p1,z)/fivept_nister::polyVal(p3,z); double y = fivept_nister::polyVal(p2,z)/fivept_nister::polyVal(p3,z); //pollishing here fivept_nister::pollishCoefficients(A,x,y,z); Evec.col(i) = x*EE.col(0) + y*EE.col(1) + z*EE.col(2) + EE.col(3); } Eigen::MatrixXd norms(1,roots.size()); for( size_t c = 0; c < roots.size(); c++ ) { norms(0,c) = 0.0; for( int r = 0; r < 9; r++ ) norms(0,c) += pow( Evec(r,c), 2 ); norms(0,c) = sqrt(norms(0,c)); } Eigen::MatrixXd EvecNorms(9,roots.size()); for( size_t i = 0; i < 9; i++ ) EvecNorms.row(i) = norms; for( size_t r = 0; r < 9; r++ ) { for( size_t c = 0; c < roots.size(); c++ ) Evec(r,c) = Evec(r,c) / EvecNorms(r,c); } for( size_t c = 0; c < roots.size(); c++ ) { essential_t essential; essential.row(0) = Evec.block<3,1>(0,c).transpose(); essential.row(1) = Evec.block<3,1>(3,c).transpose(); essential.row(2) = Evec.block<3,1>(6,c).transpose(); essentials.push_back(essential); } } void opengv::relative_pose::modules::fivept_kneip_main( const Eigen::Matrix & f1, const Eigen::Matrix & f2, rotations_t & rotations ) { Eigen::Matrix groebnerMatrix = Eigen::Matrix::Zero(); Eigen::Matrix3d temp1 = Eigen::Matrix3d::Zero(); Eigen::Matrix3d temp2 = Eigen::Matrix3d::Zero(); std::vector > c_1; c_1.push_back(temp1); c_1.push_back(temp1); c_1.push_back(temp1); std::vector > c_2; c_2.push_back(temp2); c_2.push_back(temp2); c_2.push_back(temp2); int currentRow = 0; for( int firstFeat = 0; firstFeat < 5; firstFeat++ ) { for( int secondFeat = firstFeat + 1; secondFeat < 5; secondFeat++ ) { temp1 = f1.col(firstFeat)*f1.col(secondFeat).transpose(); temp2 = f2.col(firstFeat)*f2.col(secondFeat).transpose(); for( int thirdFeat = secondFeat + 1; thirdFeat < 5; thirdFeat++ ) { c_1[0] = temp1 * f1(0,thirdFeat); c_1[1] = temp1 * f1(1,thirdFeat); c_1[2] = temp1 * f1(2,thirdFeat); c_2[0] = temp2 * f2(0,thirdFeat); c_2[1] = temp2 * f2(1,thirdFeat); c_2[2] = temp2 * f2(2,thirdFeat); groebnerMatrix.row(currentRow++) = fivept_kneip::initEpncpRowR( c_1, c_2 ); } } } fivept_kneip::initMatrix(groebnerMatrix); fivept_kneip::computeBasis(groebnerMatrix); Eigen::Matrix M = Eigen::Matrix::Zero(); M.block<10,20>(0,0) = -groebnerMatrix.block<10,20>(51,177); M(10,1) = 1.0; M(11,2) = 1.0; M(12,3) = 1.0; M(13,4) = 1.0; M(14,5) = 1.0; M(15,6) = 1.0; M(16,7) = 1.0; M(17,8) = 1.0; M(18,9) = 1.0; M(19,18) = 1.0; Eigen::EigenSolver< Eigen::Matrix > Eig(M,true); Eigen::Matrix,20,1> D = Eig.eigenvalues(); Eigen::Matrix,20,20> V = Eig.eigenvectors(); //Eigen::Matrix,9,1> tempVector; rotation_t finalRotation = Eigen::Matrix3d::Zero(); for( unsigned int i = 0; i < 20; i++ ) { std::complex tempp; tempp = D[i]; //check if we have a real solution if( fabs(tempp.imag()) < 0.1 ) { tempp = V(18,i)/V(19,i); finalRotation(0,0) = tempp.real();// tempVector[0] = tempp; tempp = V(17,i)/V(19,i); finalRotation(0,1) = tempp.real();// tempVector[1] = tempp; tempp = V(16,i)/V(19,i); finalRotation(0,2) = tempp.real();// tempVector[2] = tempp; tempp = V(15,i)/V(19,i); finalRotation(1,0) = tempp.real();// tempVector[3] = tempp; tempp = V(14,i)/V(19,i); finalRotation(1,1) = tempp.real();// tempVector[4] = tempp; tempp = V(13,i)/V(19,i); finalRotation(1,2) = tempp.real();// tempVector[5] = tempp; tempp = V(12,i)/V(19,i); finalRotation(2,0) = tempp.real();// tempVector[6] = tempp; tempp = V(11,i)/V(19,i); finalRotation(2,1) = tempp.real();// tempVector[7] = tempp; tempp = V(10,i)/V(19,i); finalRotation(2,2) = tempp.real();// tempVector[8] = tempp; double tempNorm = finalRotation.row(1).norm(); finalRotation.row(1) = finalRotation.row(1) / tempNorm; tempNorm = finalRotation.row(2).norm(); finalRotation.row(2) = finalRotation.row(2) / tempNorm; //check if the normalized rotation matrix has determinant close enough to 1 if( fabs( finalRotation.determinant() - 1.0 ) < 0.1 ) { Eigen::Matrix3d eval; double totalEval = 0.0; eval.col(0) = f1.col(0).cross(finalRotation*f2.col(0)); eval.col(1) = f1.col(1).cross(finalRotation*f2.col(1)); eval.col(2) = f1.col(2).cross(finalRotation*f2.col(2)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(0).cross(finalRotation*f2.col(0)); eval.col(1) = f1.col(1).cross(finalRotation*f2.col(1)); eval.col(2) = f1.col(3).cross(finalRotation*f2.col(3)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(0).cross(finalRotation*f2.col(0)); eval.col(1) = f1.col(1).cross(finalRotation*f2.col(1)); eval.col(2) = f1.col(4).cross(finalRotation*f2.col(4)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(0).cross(finalRotation*f2.col(0)); eval.col(1) = f1.col(2).cross(finalRotation*f2.col(2)); eval.col(2) = f1.col(3).cross(finalRotation*f2.col(3)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(0).cross(finalRotation*f2.col(0)); eval.col(1) = f1.col(2).cross(finalRotation*f2.col(2)); eval.col(2) = f1.col(4).cross(finalRotation*f2.col(4)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(0).cross(finalRotation*f2.col(0)); eval.col(1) = f1.col(3).cross(finalRotation*f2.col(3)); eval.col(2) = f1.col(4).cross(finalRotation*f2.col(4)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(1).cross(finalRotation*f2.col(1)); eval.col(1) = f1.col(2).cross(finalRotation*f2.col(2)); eval.col(2) = f1.col(3).cross(finalRotation*f2.col(3)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(1).cross(finalRotation*f2.col(1)); eval.col(1) = f1.col(2).cross(finalRotation*f2.col(2)); eval.col(2) = f1.col(4).cross(finalRotation*f2.col(4)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(1).cross(finalRotation*f2.col(1)); eval.col(1) = f1.col(3).cross(finalRotation*f2.col(3)); eval.col(2) = f1.col(4).cross(finalRotation*f2.col(4)); totalEval += fabs(eval.determinant()); eval.col(0) = f1.col(2).cross(finalRotation*f2.col(2)); eval.col(1) = f1.col(3).cross(finalRotation*f2.col(3)); eval.col(2) = f1.col(4).cross(finalRotation*f2.col(4)); totalEval += fabs(eval.determinant()); totalEval += fabs( finalRotation(0,0)*finalRotation(0,0)+ finalRotation(0,1)*finalRotation(0,1)+ finalRotation(0,2)*finalRotation(0,2)-1); totalEval += fabs( finalRotation(0,0)*finalRotation(1,0)+ finalRotation(0,1)*finalRotation(1,1)+ finalRotation(0,2)*finalRotation(1,2)); totalEval += fabs( finalRotation(0,0)*finalRotation(2,0)+ finalRotation(0,1)*finalRotation(2,1)+ finalRotation(0,2)*finalRotation(2,2)); totalEval += fabs( finalRotation(1,0)*finalRotation(1,0)+ finalRotation(1,1)*finalRotation(1,1)+ finalRotation(1,2)*finalRotation(1,2)-1); totalEval += fabs( finalRotation(1,0)*finalRotation(2,0)+ finalRotation(1,1)*finalRotation(2,1)+ finalRotation(1,2)*finalRotation(2,2)); totalEval += fabs( finalRotation(2,0)*finalRotation(2,0)+ finalRotation(2,1)*finalRotation(2,1)+ finalRotation(2,2)*finalRotation(2,2)-1); totalEval += fabs( finalRotation(1,0)*finalRotation(2,1)- finalRotation(2,0)*finalRotation(1,1)-finalRotation(0,2)); totalEval += fabs( finalRotation(2,0)*finalRotation(0,1)- finalRotation(0,0)*finalRotation(2,1)-finalRotation(1,2)); totalEval += fabs( finalRotation(0,0)*finalRotation(1,1)- finalRotation(1,0)*finalRotation(0,1)-finalRotation(2,2)); //check if the initial constraints are fullfilled to a sufficient extend if( totalEval < 0.001 ) { Eigen::Matrix normalVectors; normalVectors.col(0) = f1.col(0).cross(finalRotation * f2.col(0)); normalVectors.col(1) = f1.col(1).cross(finalRotation * f2.col(1)); normalVectors.col(2) = f1.col(2).cross(finalRotation * f2.col(2)); normalVectors.col(3) = f1.col(3).cross(finalRotation * f2.col(3)); normalVectors.col(4) = f1.col(4).cross(finalRotation * f2.col(4)); Eigen::Vector3d trans01 = normalVectors.col(0).cross(normalVectors.col(1)); Eigen::Vector3d trans02 = normalVectors.col(0).cross(normalVectors.col(2)); Eigen::Vector3d trans03 = normalVectors.col(0).cross(normalVectors.col(3)); Eigen::Vector3d trans04 = normalVectors.col(0).cross(normalVectors.col(4)); Eigen::Vector3d trans12 = normalVectors.col(1).cross(normalVectors.col(2)); Eigen::Vector3d trans13 = normalVectors.col(1).cross(normalVectors.col(3)); Eigen::Vector3d trans14 = normalVectors.col(1).cross(normalVectors.col(4)); Eigen::Vector3d trans23 = normalVectors.col(2).cross(normalVectors.col(3)); Eigen::Vector3d trans24 = normalVectors.col(2).cross(normalVectors.col(4)); Eigen::Vector3d trans34 = normalVectors.col(3).cross(normalVectors.col(4)); Eigen::Vector3d tempVector1; Eigen::Vector3d tempVector2; bool positive = true; for( int i = 0; i < 5; i++ ) { tempVector1 = trans01.cross( f1.col(i) ); tempVector2 = trans01.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans02.cross( f1.col(i) ); tempVector2 = trans02.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans03.cross( f1.col(i) ); tempVector2 = trans03.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans04.cross( f1.col(i) ); tempVector2 = trans04.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans12.cross( f1.col(i) ); tempVector2 = trans12.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans13.cross( f1.col(i) ); tempVector2 = trans13.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans14.cross( f1.col(i) ); tempVector2 = trans14.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans23.cross( f1.col(i) ); tempVector2 = trans23.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans24.cross( f1.col(i) ); tempVector2 = trans24.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } tempVector1 = trans34.cross( f1.col(i) ); tempVector2 = trans34.cross( finalRotation * f2.col(i) ); if( tempVector1.dot(tempVector2) < 0 ) { positive = false; break; } } //finally, check if the cheiriality constraint is fullfilled to //sufficient extend if( positive ) rotations.push_back(finalRotation); } } } } } namespace opengv { namespace relative_pose { namespace modules { struct Eigensolver_step : OptimizationFunctor { const Eigen::Matrix3d & _xxF; const Eigen::Matrix3d & _yyF; const Eigen::Matrix3d & _zzF; const Eigen::Matrix3d & _xyF; const Eigen::Matrix3d & _yzF; const Eigen::Matrix3d & _zxF; Eigensolver_step( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF ) : OptimizationFunctor(3,3), _xxF(xxF),_yyF(yyF),_zzF(zzF),_xyF(xyF),_yzF(yzF),_zxF(zxF) {} int operator()(const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const { cayley_t cayley = x; Eigen::Matrix jacobian; eigensolver::getSmallestEVwithJacobian( _xxF,_yyF,_zzF,_xyF,_yzF,_zxF,cayley,jacobian); fvec[0] = jacobian(0,0); fvec[1] = jacobian(0,1); fvec[2] = jacobian(0,2); return 0; } }; } } } struct myPair { EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d first; double second; }; bool operator<( const myPair & p1, const myPair & p2 ) { if( p1.second > p2.second ) return true; return false; } void opengv::relative_pose::modules::eigensolver_main( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, eigensolverOutput_t & output ) { const int n=3; VectorXd x(n); x = math::rot2cayley(output.rotation); Eigensolver_step functor(xxF,yyF,zzF,xyF,yzF,zxF ); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 0.00005; lm.parameters.xtol = 1.E1*NumTraits::epsilon(); lm.parameters.maxfev = 100; lm.minimize(x); cayley_t cayley = x; rotation_t R = math::cayley2rot(cayley); Eigen::Matrix3d M = eigensolver::composeM(xxF,yyF,zzF,xyF,yzF,zxF,cayley); Eigen::EigenSolver< Eigen::Matrix3d > Eig(M,true); Eigen::Matrix,3,1> D_complex = Eig.eigenvalues(); Eigen::Matrix,3,3> V_complex = Eig.eigenvectors(); eigenvalues_t D; eigenvectors_t V; std::vector< myPair > pairs; for(size_t i = 0; i < 3; i++) { myPair newPair; newPair.second = D_complex[i].real(); for(size_t j = 0; j < 3; j++) newPair.first(j,0) = V_complex(j,i).real(); pairs.push_back(newPair); } std::sort(pairs.begin(),pairs.end()); for(size_t i = 0; i < 3; i++) { D[i] = pairs[i].second; V.col(i) = pairs[i].first; } double translationMagnitude = sqrt(pow(D[0],2) + pow(D[1],2)); translation_t t = translationMagnitude * V.col(2); output.translation = t; output.rotation = R; output.eigenvalues = D; output.eigenvectors = V; } void opengv::relative_pose::modules::sixpt_main( Eigen::Matrix & L1, Eigen::Matrix & L2, rotations_t & solutions) { //create vectors of Pluecker coordinates std::vector< Eigen::Matrix, Eigen::aligned_allocator > > L1vec; std::vector< Eigen::Matrix, Eigen::aligned_allocator > > L2vec; for(int i = 0; i < 6; i++ ) { L1vec.push_back( L1.col(i) ); L2vec.push_back( L2.col(i) ); } //setup the action matrix Eigen::Matrix Action = Eigen::Matrix::Zero(); sixpt::setupAction( L1vec, L2vec, Action ); //finally eigen-decompose the action-matrix and obtain the solutions Eigen::EigenSolver< Eigen::Matrix > Eig(Action,true); Eigen::Matrix,64,64> EV = Eig.eigenvectors(); solutions.reserve(64); for( int c = 0; c < 64; c++ ) { cayley_t solution; for( int r = 0; r < 3; r++ ) { std::complex temp = EV(60+r,c)/EV(63,c); solution[r] = temp.real(); } solutions.push_back(math::cayley2rot(solution).transpose()); } } namespace opengv { namespace relative_pose { namespace modules { struct Ge_step : OptimizationFunctor { const Eigen::Matrix3d & _xxF; const Eigen::Matrix3d & _yyF; const Eigen::Matrix3d & _zzF; const Eigen::Matrix3d & _xyF; const Eigen::Matrix3d & _yzF; const Eigen::Matrix3d & _zxF; const Eigen::Matrix & _x1P; const Eigen::Matrix & _y1P; const Eigen::Matrix & _z1P; const Eigen::Matrix & _x2P; const Eigen::Matrix & _y2P; const Eigen::Matrix & _z2P; const Eigen::Matrix & _m11P; const Eigen::Matrix & _m12P; const Eigen::Matrix & _m22P; Ge_step( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P ) : OptimizationFunctor(3,3), _xxF(xxF),_yyF(yyF),_zzF(zzF),_xyF(xyF),_yzF(yzF),_zxF(zxF), _x1P(x1P),_y1P(y1P),_z1P(z1P),_x2P(x2P),_y2P(y2P),_z2P(z2P), _m11P(m11P),_m12P(m12P),_m22P(m22P) {} int operator()(const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const { cayley_t cayley = x; Eigen::Matrix jacobian; ge::getCostWithJacobian( _xxF,_yyF,_zzF,_xyF,_yzF,_zxF, _x1P,_y1P,_z1P,_x2P,_y2P,_z2P,_m11P,_m12P,_m22P,cayley,jacobian,1); fvec[0] = jacobian(0,0); fvec[1] = jacobian(0,1); fvec[2] = jacobian(0,2); return 0; } }; } } } struct myPair_ge { EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector4d first; double second; }; bool operator<( const myPair_ge & p1, const myPair_ge & p2 ) { if( p1.second > p2.second ) return true; return false; } void opengv::relative_pose::modules::ge_main( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & startingPoint, geOutput_t & output ) { //this one doesn't work, probably because of double numerical differentiation //use ge_main2, which is an implementation of gradient descent const int n=3; VectorXd x(n); x = startingPoint; Ge_step functor(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 0.000001;//1.E1*NumTraits::epsilon(); lm.parameters.xtol = 1.E1*NumTraits::epsilon(); lm.parameters.maxfev = 100; lm.minimize(x); cayley_t cayley = x; rotation_t R = math::cayley2rot(cayley); Eigen::Matrix4d G = ge::composeG(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley); Eigen::EigenSolver< Eigen::Matrix4d > Eig(G,true); Eigen::Matrix,4,1> D_complex = Eig.eigenvalues(); Eigen::Matrix,4,4> V_complex = Eig.eigenvectors(); Eigen::Vector4d D; Eigen::Matrix4d V; std::vector< myPair_ge > pairs; for(size_t i = 0; i < 4; i++) { myPair_ge newPair; newPair.second = D_complex[i].real(); for(size_t j = 0; j < 4; j++) newPair.first(j,0) = V_complex(j,i).real(); pairs.push_back(newPair); } std::sort(pairs.begin(),pairs.end()); for(size_t i = 0; i < 4; i++) { D[i] = pairs[i].second; V.col(i) = pairs[i].first; } double factor = V(3,3); Eigen::Vector4d t = (1.0/factor) * V.col(3); output.translation = t; output.rotation = R; output.eigenvalues = D; output.eigenvectors = V; } void opengv::relative_pose::modules::ge_main2( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & startingPoint, geOutput_t & output ) { //todo: the optimization strategy is something that can possibly be improved: //-one idea is to check the gradient at the new sampling point, if that derives // too much, we have to stop //-another idea consists of having linear change of lambda, instead of exponential (safer, but slower) double lambda = 0.01; double maxLambda = 0.08; double modifier = 2.0; int maxIterations = 50; double min_xtol = 0.00001; bool disablingIncrements = true; bool print = false; cayley_t cayley; double disturbanceAmplitude = 0.3; bool found = false; int randomTrialCount = 0; while( !found && randomTrialCount < 5 ) { if(randomTrialCount > 2) disturbanceAmplitude = 0.6; if( randomTrialCount == 0 ) cayley = startingPoint; else { cayley = startingPoint; Eigen::Vector3d disturbance; disturbance[0] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*disturbanceAmplitude; disturbance[1] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*disturbanceAmplitude; disturbance[2] = (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*disturbanceAmplitude; cayley += disturbance; } lambda = 0.01; int iterations = 0; double smallestEV = ge::getCost(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,1); while( iterations < maxIterations ) { Eigen::Matrix jacobian; ge::getQuickJacobian(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,smallestEV,jacobian,1); double norm = sqrt(pow(jacobian[0],2.0) + pow(jacobian[1],2.0) + pow(jacobian[2],2.0)); cayley_t normalizedJacobian = (1/norm) * jacobian.transpose(); cayley_t samplingPoint = cayley - lambda * normalizedJacobian; double samplingEV = ge::getCost(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,samplingPoint,1); if(print) { std::cout << iterations << ": " << samplingPoint.transpose(); std::cout << " lambda: " << lambda << " EV: " << samplingEV << std::endl; } if( iterations == 0 || !disablingIncrements ) { while( samplingEV < smallestEV ) { smallestEV = samplingEV; if( lambda * modifier > maxLambda ) break; lambda *= modifier; samplingPoint = cayley - lambda * normalizedJacobian; samplingEV = ge::getCost(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,samplingPoint,1); if(print) { std::cout << iterations << ": " << samplingPoint.transpose(); std::cout << " lambda: " << lambda << " EV: " << samplingEV << std::endl; } } } while( samplingEV > smallestEV ) { lambda /= modifier; samplingPoint = cayley - lambda * normalizedJacobian; samplingEV = ge::getCost(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,samplingPoint,1); if(print) { std::cout << iterations << ": " << samplingPoint.transpose(); std::cout << " lambda: " << lambda << " EV: " << samplingEV << std::endl; } } //apply update cayley = samplingPoint; smallestEV = samplingEV; //stopping condition (check if the update was too small) if( lambda < min_xtol ) break; iterations++; } //try to see if we can robustly identify each time we enter up in the wrong minimum if( cayley.norm() < 0.01 ) { //we are close to the origin, test the EV 2 double ev2 = ge::getCost(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,0); if( ev2 > 0.001 ) randomTrialCount++; else found = true; } else found = true; } Eigen::Matrix4d G = ge::composeG(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley); Eigen::EigenSolver< Eigen::Matrix4d > Eig(G,true); Eigen::Matrix,4,1> D_complex = Eig.eigenvalues(); Eigen::Matrix,4,4> V_complex = Eig.eigenvectors(); Eigen::Vector4d D; Eigen::Matrix4d V; std::vector< myPair_ge > pairs; for(size_t i = 0; i < 4; i++) { myPair_ge newPair; newPair.second = D_complex[i].real(); for(size_t j = 0; j < 4; j++) newPair.first(j,0) = V_complex(j,i).real(); pairs.push_back(newPair); } std::sort(pairs.begin(),pairs.end()); for(size_t i = 0; i < 4; i++) { D[i] = pairs[i].second; V.col(i) = pairs[i].first; } double factor = V(3,3); Eigen::Vector4d t = (1.0/factor) * V.col(3); output.translation = t; output.rotation = math::cayley2rot(cayley); output.eigenvalues = D; output.eigenvectors = V; } void opengv::relative_pose::modules::ge_plot( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, geOutput_t & output ) { cayley_t cayley = math::rot2cayley(output.rotation); ge::getEV(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,output.eigenvalues); output.eigenvectors = ge::composeG(xxF,yyF,zzF,xyF,yzF,zxF, x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley); } opengv/src/relative_pose/modules/fivept_nister/0000775016516101651610000000000013344612246020770 5ustar dimadimaopengv/src/relative_pose/modules/fivept_nister/modules.cpp0000664016516101651610000024770413344612246023162 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include void opengv::relative_pose::modules::fivept_nister::composeA( const Eigen::Matrix & EE, Eigen::Matrix & A) { double e00,e01,e02,e03,e04,e05,e06,e07,e08; double e10,e11,e12,e13,e14,e15,e16,e17,e18; double e20,e21,e22,e23,e24,e25,e26,e27,e28; double e30,e31,e32,e33,e34,e35,e36,e37,e38; double e002,e012,e022,e032,e042,e052,e062,e072,e082; double e102,e112,e122,e132,e142,e152,e162,e172,e182; double e202,e212,e222,e232,e242,e252,e262,e272,e282; double e302,e312,e322,e332,e342,e352,e362,e372,e382; double e003,e013,e023,e033,e043,e053,e063,e073,e083; double e103,e113,e123,e133,e143,e153,e163,e173,e183; double e203,e213,e223,e233,e243,e253,e263,e273,e283; double e303,e313,e323,e333,e343,e353,e363,e373,e383; e00 = EE(0,0); e10 = EE(0,1); e20 = EE(0,2); e30 = EE(0,3); e01 = EE(1,0); e11 = EE(1,1); e21 = EE(1,2); e31 = EE(1,3); e02 = EE(2,0); e12 = EE(2,1); e22 = EE(2,2); e32 = EE(2,3); e03 = EE(3,0); e13 = EE(3,1); e23 = EE(3,2); e33 = EE(3,3); e04 = EE(4,0); e14 = EE(4,1); e24 = EE(4,2); e34 = EE(4,3); e05 = EE(5,0); e15 = EE(5,1); e25 = EE(5,2); e35 = EE(5,3); e06 = EE(6,0); e16 = EE(6,1); e26 = EE(6,2); e36 = EE(6,3); e07 = EE(7,0); e17 = EE(7,1); e27 = EE(7,2); e37 = EE(7,3); e08 = EE(8,0); e18 = EE(8,1); e28 = EE(8,2); e38 = EE(8,3); e002 =e00*e00; e102 =e10*e10; e202 =e20*e20; e302 =e30*e30; e012 =e01*e01; e112 =e11*e11; e212 =e21*e21; e312 =e31*e31; e022 =e02*e02; e122 =e12*e12; e222 =e22*e22; e322 =e32*e32; e032 =e03*e03; e132 =e13*e13; e232 =e23*e23; e332 =e33*e33; e042 =e04*e04; e142 =e14*e14; e242 =e24*e24; e342 =e34*e34; e052 =e05*e05; e152 =e15*e15; e252 =e25*e25; e352 =e35*e35; e062 =e06*e06; e162 =e16*e16; e262 =e26*e26; e362 =e36*e36; e072 =e07*e07; e172 =e17*e17; e272 =e27*e27; e372 =e37*e37; e082 =e08*e08; e182 =e18*e18; e282 =e28*e28; e382 =e38*e38; e003 =e00*e00*e00; e103 =e10*e10*e10; e203 =e20*e20*e20; e303 =e30*e30*e30; e013 =e01*e01*e01; e113 =e11*e11*e11; e213 =e21*e21*e21; e313 =e31*e31*e31; e023 =e02*e02*e02; e123 =e12*e12*e12; e223 =e22*e22*e22; e323 =e32*e32*e32; e033 =e03*e03*e03; e133 =e13*e13*e13; e233 =e23*e23*e23; e333 =e33*e33*e33; e043 =e04*e04*e04; e143 =e14*e14*e14; e243 =e24*e24*e24; e343 =e34*e34*e34; e053 =e05*e05*e05; e153 =e15*e15*e15; e253 =e25*e25*e25; e353 =e35*e35*e35; e063 =e06*e06*e06; e163 =e16*e16*e16; e263 =e26*e26*e26; e363 =e36*e36*e36; e073 =e07*e07*e07; e173 =e17*e17*e17; e273 =e27*e27*e27; e373 =e37*e37*e37; e083 =e08*e08*e08; e183 =e18*e18*e18; e283 =e28*e28*e28; e383 =e38*e38*e38; A(0,0)=e00*e04*e08-e00*e05*e07-e01*e03*e08+e01*e05*e06+e02*e03*e07-e02*e04*e06; A(0,1)=e10*e14*e18-e10*e15*e17-e11*e13*e18+e11*e15*e16+e12*e13*e17-e12*e14*e16; A(0,2)=e00*e04*e18-e00*e05*e17-e00*e07*e15+e00*e08*e14-e01*e03*e18+e01*e05*e16+e01*e06*e15-e01*e08*e13+e02*e03*e17-e02*e04*e16-e02*e06*e14+e02*e07*e13+e03*e07*e12-e03*e08*e11-e04*e06*e12+e04*e08*e10+e05*e06*e11-e05*e07*e10; A(0,3)=e00*e14*e18-e00*e15*e17-e01*e13*e18+e01*e15*e16+e02*e13*e17-e02*e14*e16-e03*e11*e18+e03*e12*e17+e04*e10*e18-e04*e12*e16-e05*e10*e17+e05*e11*e16+e06*e11*e15-e06*e12*e14-e07*e10*e15+e07*e12*e13+e08*e10*e14-e08*e11*e13; A(0,4)=e00*e04*e28-e00*e05*e27-e00*e07*e25+e00*e08*e24-e01*e03*e28+e01*e05*e26+e01*e06*e25-e01*e08*e23+e02*e03*e27-e02*e04*e26-e02*e06*e24+e02*e07*e23+e03*e07*e22-e03*e08*e21-e04*e06*e22+e04*e08*e20+e05*e06*e21-e05*e07*e20; A(0,5)=e00*e04*e38-e00*e05*e37-e00*e07*e35+e00*e08*e34-e01*e03*e38+e01*e05*e36+e01*e06*e35-e01*e08*e33+e02*e03*e37-e02*e04*e36-e02*e06*e34+e02*e07*e33+e03*e07*e32-e03*e08*e31-e04*e06*e32+e04*e08*e30+e05*e06*e31-e05*e07*e30; A(0,6)=e10*e14*e28-e10*e15*e27-e10*e17*e25+e10*e18*e24-e11*e13*e28+e11*e15*e26+e11*e16*e25-e11*e18*e23+e12*e13*e27-e12*e14*e26-e12*e16*e24+e12*e17*e23+e13*e17*e22-e13*e18*e21-e14*e16*e22+e14*e18*e20+e15*e16*e21-e15*e17*e20; A(0,7)=e10*e14*e38-e10*e15*e37-e10*e17*e35+e10*e18*e34-e11*e13*e38+e11*e15*e36+e11*e16*e35-e11*e18*e33+e12*e13*e37-e12*e14*e36-e12*e16*e34+e12*e17*e33+e13*e17*e32-e13*e18*e31-e14*e16*e32+e14*e18*e30+e15*e16*e31-e15*e17*e30; A(0,8)=e00*e14*e28-e00*e15*e27-e00*e17*e25+e00*e18*e24-e01*e13*e28+e01*e15*e26+e01*e16*e25-e01*e18*e23+e02*e13*e27-e02*e14*e26-e02*e16*e24+e02*e17*e23-e03*e11*e28+e03*e12*e27+e03*e17*e22-e03*e18*e21+e04*e10*e28-e04*e12*e26-e04*e16*e22+e04*e18*e20-e05*e10*e27+e05*e11*e26+e05*e16*e21-e05*e17*e20+e06*e11*e25-e06*e12*e24-e06*e14*e22+e06*e15*e21-e07*e10*e25+e07*e12*e23+e07*e13*e22-e07*e15*e20+e08*e10*e24-e08*e11*e23-e08*e13*e21+e08*e14*e20; A(0,9)=e00*e14*e38-e00*e15*e37-e00*e17*e35+e00*e18*e34-e01*e13*e38+e01*e15*e36+e01*e16*e35-e01*e18*e33+e02*e13*e37-e02*e14*e36-e02*e16*e34+e02*e17*e33-e03*e11*e38+e03*e12*e37+e03*e17*e32-e03*e18*e31+e04*e10*e38-e04*e12*e36-e04*e16*e32+e04*e18*e30-e05*e10*e37+e05*e11*e36+e05*e16*e31-e05*e17*e30+e06*e11*e35-e06*e12*e34-e06*e14*e32+e06*e15*e31-e07*e10*e35+e07*e12*e33+e07*e13*e32-e07*e15*e30+e08*e10*e34-e08*e11*e33-e08*e13*e31+e08*e14*e30; A(0,10)=e00*e24*e28-e00*e25*e27-e01*e23*e28+e01*e25*e26+e02*e23*e27-e02*e24*e26-e03*e21*e28+e03*e22*e27+e04*e20*e28-e04*e22*e26-e05*e20*e27+e05*e21*e26+e06*e21*e25-e06*e22*e24-e07*e20*e25+e07*e22*e23+e08*e20*e24-e08*e21*e23; A(0,11)=e00*e24*e38-e00*e25*e37-e00*e27*e35+e00*e28*e34-e01*e23*e38+e01*e25*e36+e01*e26*e35-e01*e28*e33+e02*e23*e37-e02*e24*e36-e02*e26*e34+e02*e27*e33-e03*e21*e38+e03*e22*e37+e03*e27*e32-e03*e28*e31+e04*e20*e38-e04*e22*e36-e04*e26*e32+e04*e28*e30-e05*e20*e37+e05*e21*e36+e05*e26*e31-e05*e27*e30+e06*e21*e35-e06*e22*e34-e06*e24*e32+e06*e25*e31-e07*e20*e35+e07*e22*e33+e07*e23*e32-e07*e25*e30+e08*e20*e34-e08*e21*e33-e08*e23*e31+e08*e24*e30; A(0,12)=e00*e34*e38-e00*e35*e37-e01*e33*e38+e01*e35*e36+e02*e33*e37-e02*e34*e36-e03*e31*e38+e03*e32*e37+e04*e30*e38-e04*e32*e36-e05*e30*e37+e05*e31*e36+e06*e31*e35-e06*e32*e34-e07*e30*e35+e07*e32*e33+e08*e30*e34-e08*e31*e33; A(0,13)=e10*e24*e28-e10*e25*e27-e11*e23*e28+e11*e25*e26+e12*e23*e27-e12*e24*e26-e13*e21*e28+e13*e22*e27+e14*e20*e28-e14*e22*e26-e15*e20*e27+e15*e21*e26+e16*e21*e25-e16*e22*e24-e17*e20*e25+e17*e22*e23+e18*e20*e24-e18*e21*e23; A(0,14)=e10*e24*e38-e10*e25*e37-e10*e27*e35+e10*e28*e34-e11*e23*e38+e11*e25*e36+e11*e26*e35-e11*e28*e33+e12*e23*e37-e12*e24*e36-e12*e26*e34+e12*e27*e33-e13*e21*e38+e13*e22*e37+e13*e27*e32-e13*e28*e31+e14*e20*e38-e14*e22*e36-e14*e26*e32+e14*e28*e30-e15*e20*e37+e15*e21*e36+e15*e26*e31-e15*e27*e30+e16*e21*e35-e16*e22*e34-e16*e24*e32+e16*e25*e31-e17*e20*e35+e17*e22*e33+e17*e23*e32-e17*e25*e30+e18*e20*e34-e18*e21*e33-e18*e23*e31+e18*e24*e30; A(0,15)=e10*e34*e38-e10*e35*e37-e11*e33*e38+e11*e35*e36+e12*e33*e37-e12*e34*e36-e13*e31*e38+e13*e32*e37+e14*e30*e38-e14*e32*e36-e15*e30*e37+e15*e31*e36+e16*e31*e35-e16*e32*e34-e17*e30*e35+e17*e32*e33+e18*e30*e34-e18*e31*e33; A(0,16)=e20*e24*e28-e20*e25*e27-e21*e23*e28+e21*e25*e26+e22*e23*e27-e22*e24*e26; A(0,17)=e20*e24*e38-e20*e25*e37-e20*e27*e35+e20*e28*e34-e21*e23*e38+e21*e25*e36+e21*e26*e35-e21*e28*e33+e22*e23*e37-e22*e24*e36-e22*e26*e34+e22*e27*e33+e23*e27*e32-e23*e28*e31-e24*e26*e32+e24*e28*e30+e25*e26*e31-e25*e27*e30; A(0,18)=e20*e34*e38-e20*e35*e37-e21*e33*e38+e21*e35*e36+e22*e33*e37-e22*e34*e36-e23*e31*e38+e23*e32*e37+e24*e30*e38-e24*e32*e36-e25*e30*e37+e25*e31*e36+e26*e31*e35-e26*e32*e34-e27*e30*e35+e27*e32*e33+e28*e30*e34-e28*e31*e33; A(0,19)=e30*e34*e38-e30*e35*e37-e31*e33*e38+e31*e35*e36+e32*e33*e37-e32*e34*e36; A(1,0)=e003+e00*e012+e00*e022+e00*e032-e00*e042-e00*e052+e00*e062-e00*e072-e00*e082+2*e01*e03*e04+2*e01*e06*e07+2*e02*e03*e05+2*e02*e06*e08; A(1,1)=e103+e10*e112+e10*e122+e10*e132-e10*e142-e10*e152+e10*e162-e10*e172-e10*e182+2*e11*e13*e14+2*e11*e16*e17+2*e12*e13*e15+2*e12*e16*e18; A(1,2)=3*e002*e10+2*e00*e01*e11+2*e00*e02*e12+2*e00*e03*e13-2*e00*e04*e14-2*e00*e05*e15+2*e00*e06*e16-2*e00*e07*e17-2*e00*e08*e18+e012*e10+2*e01*e03*e14+2*e01*e04*e13+2*e01*e06*e17+2*e01*e07*e16+e022*e10+2*e02*e03*e15+2*e02*e05*e13+2*e02*e06*e18+2*e02*e08*e16+e032*e10+2*e03*e04*e11+2*e03*e05*e12-e042*e10-e052*e10+e062*e10+2*e06*e07*e11+2*e06*e08*e12-e072*e10-e082*e10; A(1,3)=3*e00*e102+e00*e112+e00*e122+e00*e132-e00*e142-e00*e152+e00*e162-e00*e172-e00*e182+2*e01*e10*e11+2*e01*e13*e14+2*e01*e16*e17+2*e02*e10*e12+2*e02*e13*e15+2*e02*e16*e18+2*e03*e10*e13+2*e03*e11*e14+2*e03*e12*e15-2*e04*e10*e14+2*e04*e11*e13-2*e05*e10*e15+2*e05*e12*e13+2*e06*e10*e16+2*e06*e11*e17+2*e06*e12*e18-2*e07*e10*e17+2*e07*e11*e16-2*e08*e10*e18+2*e08*e12*e16; A(1,4)=3*e002*e20+2*e00*e01*e21+2*e00*e02*e22+2*e00*e03*e23-2*e00*e04*e24-2*e00*e05*e25+2*e00*e06*e26-2*e00*e07*e27-2*e00*e08*e28+e012*e20+2*e01*e03*e24+2*e01*e04*e23+2*e01*e06*e27+2*e01*e07*e26+e022*e20+2*e02*e03*e25+2*e02*e05*e23+2*e02*e06*e28+2*e02*e08*e26+e032*e20+2*e03*e04*e21+2*e03*e05*e22-e042*e20-e052*e20+e062*e20+2*e06*e07*e21+2*e06*e08*e22-e072*e20-e082*e20; A(1,5)=3*e002*e30+2*e00*e01*e31+2*e00*e02*e32+2*e00*e03*e33-2*e00*e04*e34-2*e00*e05*e35+2*e00*e06*e36-2*e00*e07*e37-2*e00*e08*e38+e012*e30+2*e01*e03*e34+2*e01*e04*e33+2*e01*e06*e37+2*e01*e07*e36+e022*e30+2*e02*e03*e35+2*e02*e05*e33+2*e02*e06*e38+2*e02*e08*e36+e032*e30+2*e03*e04*e31+2*e03*e05*e32-e042*e30-e052*e30+e062*e30+2*e06*e07*e31+2*e06*e08*e32-e072*e30-e082*e30; A(1,6)=3*e102*e20+2*e10*e11*e21+2*e10*e12*e22+2*e10*e13*e23-2*e10*e14*e24-2*e10*e15*e25+2*e10*e16*e26-2*e10*e17*e27-2*e10*e18*e28+e112*e20+2*e11*e13*e24+2*e11*e14*e23+2*e11*e16*e27+2*e11*e17*e26+e122*e20+2*e12*e13*e25+2*e12*e15*e23+2*e12*e16*e28+2*e12*e18*e26+e132*e20+2*e13*e14*e21+2*e13*e15*e22-e142*e20-e152*e20+e162*e20+2*e16*e17*e21+2*e16*e18*e22-e172*e20-e182*e20; A(1,7)=3*e102*e30+2*e10*e11*e31+2*e10*e12*e32+2*e10*e13*e33-2*e10*e14*e34-2*e10*e15*e35+2*e10*e16*e36-2*e10*e17*e37-2*e10*e18*e38+e112*e30+2*e11*e13*e34+2*e11*e14*e33+2*e11*e16*e37+2*e11*e17*e36+e122*e30+2*e12*e13*e35+2*e12*e15*e33+2*e12*e16*e38+2*e12*e18*e36+e132*e30+2*e13*e14*e31+2*e13*e15*e32-e142*e30-e152*e30+e162*e30+2*e16*e17*e31+2*e16*e18*e32-e172*e30-e182*e30; A(1,8)=6*e00*e10*e20+2*e00*e11*e21+2*e00*e12*e22+2*e00*e13*e23-2*e00*e14*e24-2*e00*e15*e25+2*e00*e16*e26-2*e00*e17*e27-2*e00*e18*e28+2*e01*e10*e21+2*e01*e11*e20+2*e01*e13*e24+2*e01*e14*e23+2*e01*e16*e27+2*e01*e17*e26+2*e02*e10*e22+2*e02*e12*e20+2*e02*e13*e25+2*e02*e15*e23+2*e02*e16*e28+2*e02*e18*e26+2*e03*e10*e23+2*e03*e11*e24+2*e03*e12*e25+2*e03*e13*e20+2*e03*e14*e21+2*e03*e15*e22-2*e04*e10*e24+2*e04*e11*e23+2*e04*e13*e21-2*e04*e14*e20-2*e05*e10*e25+2*e05*e12*e23+2*e05*e13*e22-2*e05*e15*e20+2*e06*e10*e26+2*e06*e11*e27+2*e06*e12*e28+2*e06*e16*e20+2*e06*e17*e21+2*e06*e18*e22-2*e07*e10*e27+2*e07*e11*e26+2*e07*e16*e21-2*e07*e17*e20-2*e08*e10*e28+2*e08*e12*e26+2*e08*e16*e22-2*e08*e18*e20; A(1,9)=6*e00*e10*e30+2*e00*e11*e31+2*e00*e12*e32+2*e00*e13*e33-2*e00*e14*e34-2*e00*e15*e35+2*e00*e16*e36-2*e00*e17*e37-2*e00*e18*e38+2*e01*e10*e31+2*e01*e11*e30+2*e01*e13*e34+2*e01*e14*e33+2*e01*e16*e37+2*e01*e17*e36+2*e02*e10*e32+2*e02*e12*e30+2*e02*e13*e35+2*e02*e15*e33+2*e02*e16*e38+2*e02*e18*e36+2*e03*e10*e33+2*e03*e11*e34+2*e03*e12*e35+2*e03*e13*e30+2*e03*e14*e31+2*e03*e15*e32-2*e04*e10*e34+2*e04*e11*e33+2*e04*e13*e31-2*e04*e14*e30-2*e05*e10*e35+2*e05*e12*e33+2*e05*e13*e32-2*e05*e15*e30+2*e06*e10*e36+2*e06*e11*e37+2*e06*e12*e38+2*e06*e16*e30+2*e06*e17*e31+2*e06*e18*e32-2*e07*e10*e37+2*e07*e11*e36+2*e07*e16*e31-2*e07*e17*e30-2*e08*e10*e38+2*e08*e12*e36+2*e08*e16*e32-2*e08*e18*e30; A(1,10)=3*e00*e202+e00*e212+e00*e222+e00*e232-e00*e242-e00*e252+e00*e262-e00*e272-e00*e282+2*e01*e20*e21+2*e01*e23*e24+2*e01*e26*e27+2*e02*e20*e22+2*e02*e23*e25+2*e02*e26*e28+2*e03*e20*e23+2*e03*e21*e24+2*e03*e22*e25-2*e04*e20*e24+2*e04*e21*e23-2*e05*e20*e25+2*e05*e22*e23+2*e06*e20*e26+2*e06*e21*e27+2*e06*e22*e28-2*e07*e20*e27+2*e07*e21*e26-2*e08*e20*e28+2*e08*e22*e26; A(1,11)=6*e00*e20*e30+2*e00*e21*e31+2*e00*e22*e32+2*e00*e23*e33-2*e00*e24*e34-2*e00*e25*e35+2*e00*e26*e36-2*e00*e27*e37-2*e00*e28*e38+2*e01*e20*e31+2*e01*e21*e30+2*e01*e23*e34+2*e01*e24*e33+2*e01*e26*e37+2*e01*e27*e36+2*e02*e20*e32+2*e02*e22*e30+2*e02*e23*e35+2*e02*e25*e33+2*e02*e26*e38+2*e02*e28*e36+2*e03*e20*e33+2*e03*e21*e34+2*e03*e22*e35+2*e03*e23*e30+2*e03*e24*e31+2*e03*e25*e32-2*e04*e20*e34+2*e04*e21*e33+2*e04*e23*e31-2*e04*e24*e30-2*e05*e20*e35+2*e05*e22*e33+2*e05*e23*e32-2*e05*e25*e30+2*e06*e20*e36+2*e06*e21*e37+2*e06*e22*e38+2*e06*e26*e30+2*e06*e27*e31+2*e06*e28*e32-2*e07*e20*e37+2*e07*e21*e36+2*e07*e26*e31-2*e07*e27*e30-2*e08*e20*e38+2*e08*e22*e36+2*e08*e26*e32-2*e08*e28*e30; A(1,12)=3*e00*e302+e00*e312+e00*e322+e00*e332-e00*e342-e00*e352+e00*e362-e00*e372-e00*e382+2*e01*e30*e31+2*e01*e33*e34+2*e01*e36*e37+2*e02*e30*e32+2*e02*e33*e35+2*e02*e36*e38+2*e03*e30*e33+2*e03*e31*e34+2*e03*e32*e35-2*e04*e30*e34+2*e04*e31*e33-2*e05*e30*e35+2*e05*e32*e33+2*e06*e30*e36+2*e06*e31*e37+2*e06*e32*e38-2*e07*e30*e37+2*e07*e31*e36-2*e08*e30*e38+2*e08*e32*e36; A(1,13)=3*e10*e202+e10*e212+e10*e222+e10*e232-e10*e242-e10*e252+e10*e262-e10*e272-e10*e282+2*e11*e20*e21+2*e11*e23*e24+2*e11*e26*e27+2*e12*e20*e22+2*e12*e23*e25+2*e12*e26*e28+2*e13*e20*e23+2*e13*e21*e24+2*e13*e22*e25-2*e14*e20*e24+2*e14*e21*e23-2*e15*e20*e25+2*e15*e22*e23+2*e16*e20*e26+2*e16*e21*e27+2*e16*e22*e28-2*e17*e20*e27+2*e17*e21*e26-2*e18*e20*e28+2*e18*e22*e26; A(1,14)=6*e10*e20*e30+2*e10*e21*e31+2*e10*e22*e32+2*e10*e23*e33-2*e10*e24*e34-2*e10*e25*e35+2*e10*e26*e36-2*e10*e27*e37-2*e10*e28*e38+2*e11*e20*e31+2*e11*e21*e30+2*e11*e23*e34+2*e11*e24*e33+2*e11*e26*e37+2*e11*e27*e36+2*e12*e20*e32+2*e12*e22*e30+2*e12*e23*e35+2*e12*e25*e33+2*e12*e26*e38+2*e12*e28*e36+2*e13*e20*e33+2*e13*e21*e34+2*e13*e22*e35+2*e13*e23*e30+2*e13*e24*e31+2*e13*e25*e32-2*e14*e20*e34+2*e14*e21*e33+2*e14*e23*e31-2*e14*e24*e30-2*e15*e20*e35+2*e15*e22*e33+2*e15*e23*e32-2*e15*e25*e30+2*e16*e20*e36+2*e16*e21*e37+2*e16*e22*e38+2*e16*e26*e30+2*e16*e27*e31+2*e16*e28*e32-2*e17*e20*e37+2*e17*e21*e36+2*e17*e26*e31-2*e17*e27*e30-2*e18*e20*e38+2*e18*e22*e36+2*e18*e26*e32-2*e18*e28*e30; A(1,15)=3*e10*e302+e10*e312+e10*e322+e10*e332-e10*e342-e10*e352+e10*e362-e10*e372-e10*e382+2*e11*e30*e31+2*e11*e33*e34+2*e11*e36*e37+2*e12*e30*e32+2*e12*e33*e35+2*e12*e36*e38+2*e13*e30*e33+2*e13*e31*e34+2*e13*e32*e35-2*e14*e30*e34+2*e14*e31*e33-2*e15*e30*e35+2*e15*e32*e33+2*e16*e30*e36+2*e16*e31*e37+2*e16*e32*e38-2*e17*e30*e37+2*e17*e31*e36-2*e18*e30*e38+2*e18*e32*e36; A(1,16)=e203+e20*e212+e20*e222+e20*e232-e20*e242-e20*e252+e20*e262-e20*e272-e20*e282+2*e21*e23*e24+2*e21*e26*e27+2*e22*e23*e25+2*e22*e26*e28; A(1,17)=3*e202*e30+2*e20*e21*e31+2*e20*e22*e32+2*e20*e23*e33-2*e20*e24*e34-2*e20*e25*e35+2*e20*e26*e36-2*e20*e27*e37-2*e20*e28*e38+e212*e30+2*e21*e23*e34+2*e21*e24*e33+2*e21*e26*e37+2*e21*e27*e36+e222*e30+2*e22*e23*e35+2*e22*e25*e33+2*e22*e26*e38+2*e22*e28*e36+e232*e30+2*e23*e24*e31+2*e23*e25*e32-e242*e30-e252*e30+e262*e30+2*e26*e27*e31+2*e26*e28*e32-e272*e30-e282*e30; A(1,18)=3*e20*e302+e20*e312+e20*e322+e20*e332-e20*e342-e20*e352+e20*e362-e20*e372-e20*e382+2*e21*e30*e31+2*e21*e33*e34+2*e21*e36*e37+2*e22*e30*e32+2*e22*e33*e35+2*e22*e36*e38+2*e23*e30*e33+2*e23*e31*e34+2*e23*e32*e35-2*e24*e30*e34+2*e24*e31*e33-2*e25*e30*e35+2*e25*e32*e33+2*e26*e30*e36+2*e26*e31*e37+2*e26*e32*e38-2*e27*e30*e37+2*e27*e31*e36-2*e28*e30*e38+2*e28*e32*e36; A(1,19)=e303+e30*e312+e30*e322+e30*e332-e30*e342-e30*e352+e30*e362-e30*e372-e30*e382+2*e31*e33*e34+2*e31*e36*e37+2*e32*e33*e35+2*e32*e36*e38; A(2,0)=e002*e03+2*e00*e01*e04+2*e00*e02*e05-e012*e03-e022*e03+e033+e03*e042+e03*e052+e03*e062-e03*e072-e03*e082+2*e04*e06*e07+2*e05*e06*e08; A(2,1)=e102*e13+2*e10*e11*e14+2*e10*e12*e15-e112*e13-e122*e13+e133+e13*e142+e13*e152+e13*e162-e13*e172-e13*e182+2*e14*e16*e17+2*e15*e16*e18; A(2,2)=e002*e13+2*e00*e01*e14+2*e00*e02*e15+2*e00*e03*e10+2*e00*e04*e11+2*e00*e05*e12-e012*e13-2*e01*e03*e11+2*e01*e04*e10-e022*e13-2*e02*e03*e12+2*e02*e05*e10+3*e032*e13+2*e03*e04*e14+2*e03*e05*e15+2*e03*e06*e16-2*e03*e07*e17-2*e03*e08*e18+e042*e13+2*e04*e06*e17+2*e04*e07*e16+e052*e13+2*e05*e06*e18+2*e05*e08*e16+e062*e13+2*e06*e07*e14+2*e06*e08*e15-e072*e13-e082*e13; A(2,3)=2*e00*e10*e13+2*e00*e11*e14+2*e00*e12*e15+2*e01*e10*e14-2*e01*e11*e13+2*e02*e10*e15-2*e02*e12*e13+e03*e102-e03*e112-e03*e122+3*e03*e132+e03*e142+e03*e152+e03*e162-e03*e172-e03*e182+2*e04*e10*e11+2*e04*e13*e14+2*e04*e16*e17+2*e05*e10*e12+2*e05*e13*e15+2*e05*e16*e18+2*e06*e13*e16+2*e06*e14*e17+2*e06*e15*e18-2*e07*e13*e17+2*e07*e14*e16-2*e08*e13*e18+2*e08*e15*e16; A(2,4)=e002*e23+2*e00*e01*e24+2*e00*e02*e25+2*e00*e03*e20+2*e00*e04*e21+2*e00*e05*e22-e012*e23-2*e01*e03*e21+2*e01*e04*e20-e022*e23-2*e02*e03*e22+2*e02*e05*e20+3*e032*e23+2*e03*e04*e24+2*e03*e05*e25+2*e03*e06*e26-2*e03*e07*e27-2*e03*e08*e28+e042*e23+2*e04*e06*e27+2*e04*e07*e26+e052*e23+2*e05*e06*e28+2*e05*e08*e26+e062*e23+2*e06*e07*e24+2*e06*e08*e25-e072*e23-e082*e23; A(2,5)=e002*e33+2*e00*e01*e34+2*e00*e02*e35+2*e00*e03*e30+2*e00*e04*e31+2*e00*e05*e32-e012*e33-2*e01*e03*e31+2*e01*e04*e30-e022*e33-2*e02*e03*e32+2*e02*e05*e30+3*e032*e33+2*e03*e04*e34+2*e03*e05*e35+2*e03*e06*e36-2*e03*e07*e37-2*e03*e08*e38+e042*e33+2*e04*e06*e37+2*e04*e07*e36+e052*e33+2*e05*e06*e38+2*e05*e08*e36+e062*e33+2*e06*e07*e34+2*e06*e08*e35-e072*e33-e082*e33; A(2,6)=e102*e23+2*e10*e11*e24+2*e10*e12*e25+2*e10*e13*e20+2*e10*e14*e21+2*e10*e15*e22-e112*e23-2*e11*e13*e21+2*e11*e14*e20-e122*e23-2*e12*e13*e22+2*e12*e15*e20+3*e132*e23+2*e13*e14*e24+2*e13*e15*e25+2*e13*e16*e26-2*e13*e17*e27-2*e13*e18*e28+e142*e23+2*e14*e16*e27+2*e14*e17*e26+e152*e23+2*e15*e16*e28+2*e15*e18*e26+e162*e23+2*e16*e17*e24+2*e16*e18*e25-e172*e23-e182*e23; A(2,7)=e102*e33+2*e10*e11*e34+2*e10*e12*e35+2*e10*e13*e30+2*e10*e14*e31+2*e10*e15*e32-e112*e33-2*e11*e13*e31+2*e11*e14*e30-e122*e33-2*e12*e13*e32+2*e12*e15*e30+3*e132*e33+2*e13*e14*e34+2*e13*e15*e35+2*e13*e16*e36-2*e13*e17*e37-2*e13*e18*e38+e142*e33+2*e14*e16*e37+2*e14*e17*e36+e152*e33+2*e15*e16*e38+2*e15*e18*e36+e162*e33+2*e16*e17*e34+2*e16*e18*e35-e172*e33-e182*e33; A(2,8)=2*e00*e10*e23+2*e00*e11*e24+2*e00*e12*e25+2*e00*e13*e20+2*e00*e14*e21+2*e00*e15*e22+2*e01*e10*e24-2*e01*e11*e23-2*e01*e13*e21+2*e01*e14*e20+2*e02*e10*e25-2*e02*e12*e23-2*e02*e13*e22+2*e02*e15*e20+2*e03*e10*e20-2*e03*e11*e21-2*e03*e12*e22+6*e03*e13*e23+2*e03*e14*e24+2*e03*e15*e25+2*e03*e16*e26-2*e03*e17*e27-2*e03*e18*e28+2*e04*e10*e21+2*e04*e11*e20+2*e04*e13*e24+2*e04*e14*e23+2*e04*e16*e27+2*e04*e17*e26+2*e05*e10*e22+2*e05*e12*e20+2*e05*e13*e25+2*e05*e15*e23+2*e05*e16*e28+2*e05*e18*e26+2*e06*e13*e26+2*e06*e14*e27+2*e06*e15*e28+2*e06*e16*e23+2*e06*e17*e24+2*e06*e18*e25-2*e07*e13*e27+2*e07*e14*e26+2*e07*e16*e24-2*e07*e17*e23-2*e08*e13*e28+2*e08*e15*e26+2*e08*e16*e25-2*e08*e18*e23; A(2,9)=2*e00*e10*e33+2*e00*e11*e34+2*e00*e12*e35+2*e00*e13*e30+2*e00*e14*e31+2*e00*e15*e32+2*e01*e10*e34-2*e01*e11*e33-2*e01*e13*e31+2*e01*e14*e30+2*e02*e10*e35-2*e02*e12*e33-2*e02*e13*e32+2*e02*e15*e30+2*e03*e10*e30-2*e03*e11*e31-2*e03*e12*e32+6*e03*e13*e33+2*e03*e14*e34+2*e03*e15*e35+2*e03*e16*e36-2*e03*e17*e37-2*e03*e18*e38+2*e04*e10*e31+2*e04*e11*e30+2*e04*e13*e34+2*e04*e14*e33+2*e04*e16*e37+2*e04*e17*e36+2*e05*e10*e32+2*e05*e12*e30+2*e05*e13*e35+2*e05*e15*e33+2*e05*e16*e38+2*e05*e18*e36+2*e06*e13*e36+2*e06*e14*e37+2*e06*e15*e38+2*e06*e16*e33+2*e06*e17*e34+2*e06*e18*e35-2*e07*e13*e37+2*e07*e14*e36+2*e07*e16*e34-2*e07*e17*e33-2*e08*e13*e38+2*e08*e15*e36+2*e08*e16*e35-2*e08*e18*e33; A(2,10)=2*e00*e20*e23+2*e00*e21*e24+2*e00*e22*e25+2*e01*e20*e24-2*e01*e21*e23+2*e02*e20*e25-2*e02*e22*e23+e03*e202-e03*e212-e03*e222+3*e03*e232+e03*e242+e03*e252+e03*e262-e03*e272-e03*e282+2*e04*e20*e21+2*e04*e23*e24+2*e04*e26*e27+2*e05*e20*e22+2*e05*e23*e25+2*e05*e26*e28+2*e06*e23*e26+2*e06*e24*e27+2*e06*e25*e28-2*e07*e23*e27+2*e07*e24*e26-2*e08*e23*e28+2*e08*e25*e26; A(2,11)=2*e00*e20*e33+2*e00*e21*e34+2*e00*e22*e35+2*e00*e23*e30+2*e00*e24*e31+2*e00*e25*e32+2*e01*e20*e34-2*e01*e21*e33-2*e01*e23*e31+2*e01*e24*e30+2*e02*e20*e35-2*e02*e22*e33-2*e02*e23*e32+2*e02*e25*e30+2*e03*e20*e30-2*e03*e21*e31-2*e03*e22*e32+6*e03*e23*e33+2*e03*e24*e34+2*e03*e25*e35+2*e03*e26*e36-2*e03*e27*e37-2*e03*e28*e38+2*e04*e20*e31+2*e04*e21*e30+2*e04*e23*e34+2*e04*e24*e33+2*e04*e26*e37+2*e04*e27*e36+2*e05*e20*e32+2*e05*e22*e30+2*e05*e23*e35+2*e05*e25*e33+2*e05*e26*e38+2*e05*e28*e36+2*e06*e23*e36+2*e06*e24*e37+2*e06*e25*e38+2*e06*e26*e33+2*e06*e27*e34+2*e06*e28*e35-2*e07*e23*e37+2*e07*e24*e36+2*e07*e26*e34-2*e07*e27*e33-2*e08*e23*e38+2*e08*e25*e36+2*e08*e26*e35-2*e08*e28*e33; A(2,12)=2*e00*e30*e33+2*e00*e31*e34+2*e00*e32*e35+2*e01*e30*e34-2*e01*e31*e33+2*e02*e30*e35-2*e02*e32*e33+e03*e302-e03*e312-e03*e322+3*e03*e332+e03*e342+e03*e352+e03*e362-e03*e372-e03*e382+2*e04*e30*e31+2*e04*e33*e34+2*e04*e36*e37+2*e05*e30*e32+2*e05*e33*e35+2*e05*e36*e38+2*e06*e33*e36+2*e06*e34*e37+2*e06*e35*e38-2*e07*e33*e37+2*e07*e34*e36-2*e08*e33*e38+2*e08*e35*e36; A(2,13)=2*e10*e20*e23+2*e10*e21*e24+2*e10*e22*e25+2*e11*e20*e24-2*e11*e21*e23+2*e12*e20*e25-2*e12*e22*e23+e13*e202-e13*e212-e13*e222+3*e13*e232+e13*e242+e13*e252+e13*e262-e13*e272-e13*e282+2*e14*e20*e21+2*e14*e23*e24+2*e14*e26*e27+2*e15*e20*e22+2*e15*e23*e25+2*e15*e26*e28+2*e16*e23*e26+2*e16*e24*e27+2*e16*e25*e28-2*e17*e23*e27+2*e17*e24*e26-2*e18*e23*e28+2*e18*e25*e26; A(2,14)=2*e10*e20*e33+2*e10*e21*e34+2*e10*e22*e35+2*e10*e23*e30+2*e10*e24*e31+2*e10*e25*e32+2*e11*e20*e34-2*e11*e21*e33-2*e11*e23*e31+2*e11*e24*e30+2*e12*e20*e35-2*e12*e22*e33-2*e12*e23*e32+2*e12*e25*e30+2*e13*e20*e30-2*e13*e21*e31-2*e13*e22*e32+6*e13*e23*e33+2*e13*e24*e34+2*e13*e25*e35+2*e13*e26*e36-2*e13*e27*e37-2*e13*e28*e38+2*e14*e20*e31+2*e14*e21*e30+2*e14*e23*e34+2*e14*e24*e33+2*e14*e26*e37+2*e14*e27*e36+2*e15*e20*e32+2*e15*e22*e30+2*e15*e23*e35+2*e15*e25*e33+2*e15*e26*e38+2*e15*e28*e36+2*e16*e23*e36+2*e16*e24*e37+2*e16*e25*e38+2*e16*e26*e33+2*e16*e27*e34+2*e16*e28*e35-2*e17*e23*e37+2*e17*e24*e36+2*e17*e26*e34-2*e17*e27*e33-2*e18*e23*e38+2*e18*e25*e36+2*e18*e26*e35-2*e18*e28*e33; A(2,15)=2*e10*e30*e33+2*e10*e31*e34+2*e10*e32*e35+2*e11*e30*e34-2*e11*e31*e33+2*e12*e30*e35-2*e12*e32*e33+e13*e302-e13*e312-e13*e322+3*e13*e332+e13*e342+e13*e352+e13*e362-e13*e372-e13*e382+2*e14*e30*e31+2*e14*e33*e34+2*e14*e36*e37+2*e15*e30*e32+2*e15*e33*e35+2*e15*e36*e38+2*e16*e33*e36+2*e16*e34*e37+2*e16*e35*e38-2*e17*e33*e37+2*e17*e34*e36-2*e18*e33*e38+2*e18*e35*e36; A(2,16)=e202*e23+2*e20*e21*e24+2*e20*e22*e25-e212*e23-e222*e23+e233+e23*e242+e23*e252+e23*e262-e23*e272-e23*e282+2*e24*e26*e27+2*e25*e26*e28; A(2,17)=e202*e33+2*e20*e21*e34+2*e20*e22*e35+2*e20*e23*e30+2*e20*e24*e31+2*e20*e25*e32-e212*e33-2*e21*e23*e31+2*e21*e24*e30-e222*e33-2*e22*e23*e32+2*e22*e25*e30+3*e232*e33+2*e23*e24*e34+2*e23*e25*e35+2*e23*e26*e36-2*e23*e27*e37-2*e23*e28*e38+e242*e33+2*e24*e26*e37+2*e24*e27*e36+e252*e33+2*e25*e26*e38+2*e25*e28*e36+e262*e33+2*e26*e27*e34+2*e26*e28*e35-e272*e33-e282*e33; A(2,18)=2*e20*e30*e33+2*e20*e31*e34+2*e20*e32*e35+2*e21*e30*e34-2*e21*e31*e33+2*e22*e30*e35-2*e22*e32*e33+e23*e302-e23*e312-e23*e322+3*e23*e332+e23*e342+e23*e352+e23*e362-e23*e372-e23*e382+2*e24*e30*e31+2*e24*e33*e34+2*e24*e36*e37+2*e25*e30*e32+2*e25*e33*e35+2*e25*e36*e38+2*e26*e33*e36+2*e26*e34*e37+2*e26*e35*e38-2*e27*e33*e37+2*e27*e34*e36-2*e28*e33*e38+2*e28*e35*e36; A(2,19)=e302*e33+2*e30*e31*e34+2*e30*e32*e35-e312*e33-e322*e33+e333+e33*e342+e33*e352+e33*e362-e33*e372-e33*e382+2*e34*e36*e37+2*e35*e36*e38; A(3,0)=e002*e06+2*e00*e01*e07+2*e00*e02*e08-e012*e06-e022*e06+e032*e06+2*e03*e04*e07+2*e03*e05*e08-e042*e06-e052*e06+e063+e06*e072+e06*e082; A(3,1)=e102*e16+2*e10*e11*e17+2*e10*e12*e18-e112*e16-e122*e16+e132*e16+2*e13*e14*e17+2*e13*e15*e18-e142*e16-e152*e16+e163+e16*e172+e16*e182; A(3,2)=e002*e16+2*e00*e01*e17+2*e00*e02*e18+2*e00*e06*e10+2*e00*e07*e11+2*e00*e08*e12-e012*e16-2*e01*e06*e11+2*e01*e07*e10-e022*e16-2*e02*e06*e12+2*e02*e08*e10+e032*e16+2*e03*e04*e17+2*e03*e05*e18+2*e03*e06*e13+2*e03*e07*e14+2*e03*e08*e15-e042*e16-2*e04*e06*e14+2*e04*e07*e13-e052*e16-2*e05*e06*e15+2*e05*e08*e13+3*e062*e16+2*e06*e07*e17+2*e06*e08*e18+e072*e16+e082*e16; A(3,3)=2*e00*e10*e16+2*e00*e11*e17+2*e00*e12*e18+2*e01*e10*e17-2*e01*e11*e16+2*e02*e10*e18-2*e02*e12*e16+2*e03*e13*e16+2*e03*e14*e17+2*e03*e15*e18+2*e04*e13*e17-2*e04*e14*e16+2*e05*e13*e18-2*e05*e15*e16+e06*e102-e06*e112-e06*e122+e06*e132-e06*e142-e06*e152+3*e06*e162+e06*e172+e06*e182+2*e07*e10*e11+2*e07*e13*e14+2*e07*e16*e17+2*e08*e10*e12+2*e08*e13*e15+2*e08*e16*e18; A(3,4)=e002*e26+2*e00*e01*e27+2*e00*e02*e28+2*e00*e06*e20+2*e00*e07*e21+2*e00*e08*e22-e012*e26-2*e01*e06*e21+2*e01*e07*e20-e022*e26-2*e02*e06*e22+2*e02*e08*e20+e032*e26+2*e03*e04*e27+2*e03*e05*e28+2*e03*e06*e23+2*e03*e07*e24+2*e03*e08*e25-e042*e26-2*e04*e06*e24+2*e04*e07*e23-e052*e26-2*e05*e06*e25+2*e05*e08*e23+3*e062*e26+2*e06*e07*e27+2*e06*e08*e28+e072*e26+e082*e26; A(3,5)=e002*e36+2*e00*e01*e37+2*e00*e02*e38+2*e00*e06*e30+2*e00*e07*e31+2*e00*e08*e32-e012*e36-2*e01*e06*e31+2*e01*e07*e30-e022*e36-2*e02*e06*e32+2*e02*e08*e30+e032*e36+2*e03*e04*e37+2*e03*e05*e38+2*e03*e06*e33+2*e03*e07*e34+2*e03*e08*e35-e042*e36-2*e04*e06*e34+2*e04*e07*e33-e052*e36-2*e05*e06*e35+2*e05*e08*e33+3*e062*e36+2*e06*e07*e37+2*e06*e08*e38+e072*e36+e082*e36; A(3,6)=e102*e26+2*e10*e11*e27+2*e10*e12*e28+2*e10*e16*e20+2*e10*e17*e21+2*e10*e18*e22-e112*e26-2*e11*e16*e21+2*e11*e17*e20-e122*e26-2*e12*e16*e22+2*e12*e18*e20+e132*e26+2*e13*e14*e27+2*e13*e15*e28+2*e13*e16*e23+2*e13*e17*e24+2*e13*e18*e25-e142*e26-2*e14*e16*e24+2*e14*e17*e23-e152*e26-2*e15*e16*e25+2*e15*e18*e23+3*e162*e26+2*e16*e17*e27+2*e16*e18*e28+e172*e26+e182*e26; A(3,7)=e102*e36+2*e10*e11*e37+2*e10*e12*e38+2*e10*e16*e30+2*e10*e17*e31+2*e10*e18*e32-e112*e36-2*e11*e16*e31+2*e11*e17*e30-e122*e36-2*e12*e16*e32+2*e12*e18*e30+e132*e36+2*e13*e14*e37+2*e13*e15*e38+2*e13*e16*e33+2*e13*e17*e34+2*e13*e18*e35-e142*e36-2*e14*e16*e34+2*e14*e17*e33-e152*e36-2*e15*e16*e35+2*e15*e18*e33+3*e162*e36+2*e16*e17*e37+2*e16*e18*e38+e172*e36+e182*e36; A(3,8)=2*e00*e10*e26+2*e00*e11*e27+2*e00*e12*e28+2*e00*e16*e20+2*e00*e17*e21+2*e00*e18*e22+2*e01*e10*e27-2*e01*e11*e26-2*e01*e16*e21+2*e01*e17*e20+2*e02*e10*e28-2*e02*e12*e26-2*e02*e16*e22+2*e02*e18*e20+2*e03*e13*e26+2*e03*e14*e27+2*e03*e15*e28+2*e03*e16*e23+2*e03*e17*e24+2*e03*e18*e25+2*e04*e13*e27-2*e04*e14*e26-2*e04*e16*e24+2*e04*e17*e23+2*e05*e13*e28-2*e05*e15*e26-2*e05*e16*e25+2*e05*e18*e23+2*e06*e10*e20-2*e06*e11*e21-2*e06*e12*e22+2*e06*e13*e23-2*e06*e14*e24-2*e06*e15*e25+6*e06*e16*e26+2*e06*e17*e27+2*e06*e18*e28+2*e07*e10*e21+2*e07*e11*e20+2*e07*e13*e24+2*e07*e14*e23+2*e07*e16*e27+2*e07*e17*e26+2*e08*e10*e22+2*e08*e12*e20+2*e08*e13*e25+2*e08*e15*e23+2*e08*e16*e28+2*e08*e18*e26; A(3,9)=2*e00*e10*e36+2*e00*e11*e37+2*e00*e12*e38+2*e00*e16*e30+2*e00*e17*e31+2*e00*e18*e32+2*e01*e10*e37-2*e01*e11*e36-2*e01*e16*e31+2*e01*e17*e30+2*e02*e10*e38-2*e02*e12*e36-2*e02*e16*e32+2*e02*e18*e30+2*e03*e13*e36+2*e03*e14*e37+2*e03*e15*e38+2*e03*e16*e33+2*e03*e17*e34+2*e03*e18*e35+2*e04*e13*e37-2*e04*e14*e36-2*e04*e16*e34+2*e04*e17*e33+2*e05*e13*e38-2*e05*e15*e36-2*e05*e16*e35+2*e05*e18*e33+2*e06*e10*e30-2*e06*e11*e31-2*e06*e12*e32+2*e06*e13*e33-2*e06*e14*e34-2*e06*e15*e35+6*e06*e16*e36+2*e06*e17*e37+2*e06*e18*e38+2*e07*e10*e31+2*e07*e11*e30+2*e07*e13*e34+2*e07*e14*e33+2*e07*e16*e37+2*e07*e17*e36+2*e08*e10*e32+2*e08*e12*e30+2*e08*e13*e35+2*e08*e15*e33+2*e08*e16*e38+2*e08*e18*e36; A(3,10)=2*e00*e20*e26+2*e00*e21*e27+2*e00*e22*e28+2*e01*e20*e27-2*e01*e21*e26+2*e02*e20*e28-2*e02*e22*e26+2*e03*e23*e26+2*e03*e24*e27+2*e03*e25*e28+2*e04*e23*e27-2*e04*e24*e26+2*e05*e23*e28-2*e05*e25*e26+e06*e202-e06*e212-e06*e222+e06*e232-e06*e242-e06*e252+3*e06*e262+e06*e272+e06*e282+2*e07*e20*e21+2*e07*e23*e24+2*e07*e26*e27+2*e08*e20*e22+2*e08*e23*e25+2*e08*e26*e28; A(3,11)=2*e00*e20*e36+2*e00*e21*e37+2*e00*e22*e38+2*e00*e26*e30+2*e00*e27*e31+2*e00*e28*e32+2*e01*e20*e37-2*e01*e21*e36-2*e01*e26*e31+2*e01*e27*e30+2*e02*e20*e38-2*e02*e22*e36-2*e02*e26*e32+2*e02*e28*e30+2*e03*e23*e36+2*e03*e24*e37+2*e03*e25*e38+2*e03*e26*e33+2*e03*e27*e34+2*e03*e28*e35+2*e04*e23*e37-2*e04*e24*e36-2*e04*e26*e34+2*e04*e27*e33+2*e05*e23*e38-2*e05*e25*e36-2*e05*e26*e35+2*e05*e28*e33+2*e06*e20*e30-2*e06*e21*e31-2*e06*e22*e32+2*e06*e23*e33-2*e06*e24*e34-2*e06*e25*e35+6*e06*e26*e36+2*e06*e27*e37+2*e06*e28*e38+2*e07*e20*e31+2*e07*e21*e30+2*e07*e23*e34+2*e07*e24*e33+2*e07*e26*e37+2*e07*e27*e36+2*e08*e20*e32+2*e08*e22*e30+2*e08*e23*e35+2*e08*e25*e33+2*e08*e26*e38+2*e08*e28*e36; A(3,12)=2*e00*e30*e36+2*e00*e31*e37+2*e00*e32*e38+2*e01*e30*e37-2*e01*e31*e36+2*e02*e30*e38-2*e02*e32*e36+2*e03*e33*e36+2*e03*e34*e37+2*e03*e35*e38+2*e04*e33*e37-2*e04*e34*e36+2*e05*e33*e38-2*e05*e35*e36+e06*e302-e06*e312-e06*e322+e06*e332-e06*e342-e06*e352+3*e06*e362+e06*e372+e06*e382+2*e07*e30*e31+2*e07*e33*e34+2*e07*e36*e37+2*e08*e30*e32+2*e08*e33*e35+2*e08*e36*e38; A(3,13)=2*e10*e20*e26+2*e10*e21*e27+2*e10*e22*e28+2*e11*e20*e27-2*e11*e21*e26+2*e12*e20*e28-2*e12*e22*e26+2*e13*e23*e26+2*e13*e24*e27+2*e13*e25*e28+2*e14*e23*e27-2*e14*e24*e26+2*e15*e23*e28-2*e15*e25*e26+e16*e202-e16*e212-e16*e222+e16*e232-e16*e242-e16*e252+3*e16*e262+e16*e272+e16*e282+2*e17*e20*e21+2*e17*e23*e24+2*e17*e26*e27+2*e18*e20*e22+2*e18*e23*e25+2*e18*e26*e28; A(3,14)=2*e10*e20*e36+2*e10*e21*e37+2*e10*e22*e38+2*e10*e26*e30+2*e10*e27*e31+2*e10*e28*e32+2*e11*e20*e37-2*e11*e21*e36-2*e11*e26*e31+2*e11*e27*e30+2*e12*e20*e38-2*e12*e22*e36-2*e12*e26*e32+2*e12*e28*e30+2*e13*e23*e36+2*e13*e24*e37+2*e13*e25*e38+2*e13*e26*e33+2*e13*e27*e34+2*e13*e28*e35+2*e14*e23*e37-2*e14*e24*e36-2*e14*e26*e34+2*e14*e27*e33+2*e15*e23*e38-2*e15*e25*e36-2*e15*e26*e35+2*e15*e28*e33+2*e16*e20*e30-2*e16*e21*e31-2*e16*e22*e32+2*e16*e23*e33-2*e16*e24*e34-2*e16*e25*e35+6*e16*e26*e36+2*e16*e27*e37+2*e16*e28*e38+2*e17*e20*e31+2*e17*e21*e30+2*e17*e23*e34+2*e17*e24*e33+2*e17*e26*e37+2*e17*e27*e36+2*e18*e20*e32+2*e18*e22*e30+2*e18*e23*e35+2*e18*e25*e33+2*e18*e26*e38+2*e18*e28*e36; A(3,15)=2*e10*e30*e36+2*e10*e31*e37+2*e10*e32*e38+2*e11*e30*e37-2*e11*e31*e36+2*e12*e30*e38-2*e12*e32*e36+2*e13*e33*e36+2*e13*e34*e37+2*e13*e35*e38+2*e14*e33*e37-2*e14*e34*e36+2*e15*e33*e38-2*e15*e35*e36+e16*e302-e16*e312-e16*e322+e16*e332-e16*e342-e16*e352+3*e16*e362+e16*e372+e16*e382+2*e17*e30*e31+2*e17*e33*e34+2*e17*e36*e37+2*e18*e30*e32+2*e18*e33*e35+2*e18*e36*e38; A(3,16)=e202*e26+2*e20*e21*e27+2*e20*e22*e28-e212*e26-e222*e26+e232*e26+2*e23*e24*e27+2*e23*e25*e28-e242*e26-e252*e26+e263+e26*e272+e26*e282; A(3,17)=e202*e36+2*e20*e21*e37+2*e20*e22*e38+2*e20*e26*e30+2*e20*e27*e31+2*e20*e28*e32-e212*e36-2*e21*e26*e31+2*e21*e27*e30-e222*e36-2*e22*e26*e32+2*e22*e28*e30+e232*e36+2*e23*e24*e37+2*e23*e25*e38+2*e23*e26*e33+2*e23*e27*e34+2*e23*e28*e35-e242*e36-2*e24*e26*e34+2*e24*e27*e33-e252*e36-2*e25*e26*e35+2*e25*e28*e33+3*e262*e36+2*e26*e27*e37+2*e26*e28*e38+e272*e36+e282*e36; A(3,18)=2*e20*e30*e36+2*e20*e31*e37+2*e20*e32*e38+2*e21*e30*e37-2*e21*e31*e36+2*e22*e30*e38-2*e22*e32*e36+2*e23*e33*e36+2*e23*e34*e37+2*e23*e35*e38+2*e24*e33*e37-2*e24*e34*e36+2*e25*e33*e38-2*e25*e35*e36+e26*e302-e26*e312-e26*e322+e26*e332-e26*e342-e26*e352+3*e26*e362+e26*e372+e26*e382+2*e27*e30*e31+2*e27*e33*e34+2*e27*e36*e37+2*e28*e30*e32+2*e28*e33*e35+2*e28*e36*e38; A(3,19)=e302*e36+2*e30*e31*e37+2*e30*e32*e38-e312*e36-e322*e36+e332*e36+2*e33*e34*e37+2*e33*e35*e38-e342*e36-e352*e36+e363+e36*e372+e36*e382; A(4,0)=e002*e01+2*e00*e03*e04+2*e00*e06*e07+e013+e01*e022-e01*e032+e01*e042-e01*e052-e01*e062+e01*e072-e01*e082+2*e02*e04*e05+2*e02*e07*e08; A(4,1)=e102*e11+2*e10*e13*e14+2*e10*e16*e17+e113+e11*e122-e11*e132+e11*e142-e11*e152-e11*e162+e11*e172-e11*e182+2*e12*e14*e15+2*e12*e17*e18; A(4,2)=e002*e11+2*e00*e01*e10+2*e00*e03*e14+2*e00*e04*e13+2*e00*e06*e17+2*e00*e07*e16+3*e012*e11+2*e01*e02*e12-2*e01*e03*e13+2*e01*e04*e14-2*e01*e05*e15-2*e01*e06*e16+2*e01*e07*e17-2*e01*e08*e18+e022*e11+2*e02*e04*e15+2*e02*e05*e14+2*e02*e07*e18+2*e02*e08*e17-e032*e11+2*e03*e04*e10+e042*e11+2*e04*e05*e12-e052*e11-e062*e11+2*e06*e07*e10+e072*e11+2*e07*e08*e12-e082*e11; A(4,3)=2*e00*e10*e11+2*e00*e13*e14+2*e00*e16*e17+e01*e102+3*e01*e112+e01*e122-e01*e132+e01*e142-e01*e152-e01*e162+e01*e172-e01*e182+2*e02*e11*e12+2*e02*e14*e15+2*e02*e17*e18+2*e03*e10*e14-2*e03*e11*e13+2*e04*e10*e13+2*e04*e11*e14+2*e04*e12*e15-2*e05*e11*e15+2*e05*e12*e14+2*e06*e10*e17-2*e06*e11*e16+2*e07*e10*e16+2*e07*e11*e17+2*e07*e12*e18-2*e08*e11*e18+2*e08*e12*e17; A(4,4)=e002*e21+2*e00*e01*e20+2*e00*e03*e24+2*e00*e04*e23+2*e00*e06*e27+2*e00*e07*e26+3*e012*e21+2*e01*e02*e22-2*e01*e03*e23+2*e01*e04*e24-2*e01*e05*e25-2*e01*e06*e26+2*e01*e07*e27-2*e01*e08*e28+e022*e21+2*e02*e04*e25+2*e02*e05*e24+2*e02*e07*e28+2*e02*e08*e27-e032*e21+2*e03*e04*e20+e042*e21+2*e04*e05*e22-e052*e21-e062*e21+2*e06*e07*e20+e072*e21+2*e07*e08*e22-e082*e21; A(4,5)=e002*e31+2*e00*e01*e30+2*e00*e03*e34+2*e00*e04*e33+2*e00*e06*e37+2*e00*e07*e36+3*e012*e31+2*e01*e02*e32-2*e01*e03*e33+2*e01*e04*e34-2*e01*e05*e35-2*e01*e06*e36+2*e01*e07*e37-2*e01*e08*e38+e022*e31+2*e02*e04*e35+2*e02*e05*e34+2*e02*e07*e38+2*e02*e08*e37-e032*e31+2*e03*e04*e30+e042*e31+2*e04*e05*e32-e052*e31-e062*e31+2*e06*e07*e30+e072*e31+2*e07*e08*e32-e082*e31; A(4,6)=e102*e21+2*e10*e11*e20+2*e10*e13*e24+2*e10*e14*e23+2*e10*e16*e27+2*e10*e17*e26+3*e112*e21+2*e11*e12*e22-2*e11*e13*e23+2*e11*e14*e24-2*e11*e15*e25-2*e11*e16*e26+2*e11*e17*e27-2*e11*e18*e28+e122*e21+2*e12*e14*e25+2*e12*e15*e24+2*e12*e17*e28+2*e12*e18*e27-e132*e21+2*e13*e14*e20+e142*e21+2*e14*e15*e22-e152*e21-e162*e21+2*e16*e17*e20+e172*e21+2*e17*e18*e22-e182*e21; A(4,7)=e102*e31+2*e10*e11*e30+2*e10*e13*e34+2*e10*e14*e33+2*e10*e16*e37+2*e10*e17*e36+3*e112*e31+2*e11*e12*e32-2*e11*e13*e33+2*e11*e14*e34-2*e11*e15*e35-2*e11*e16*e36+2*e11*e17*e37-2*e11*e18*e38+e122*e31+2*e12*e14*e35+2*e12*e15*e34+2*e12*e17*e38+2*e12*e18*e37-e132*e31+2*e13*e14*e30+e142*e31+2*e14*e15*e32-e152*e31-e162*e31+2*e16*e17*e30+e172*e31+2*e17*e18*e32-e182*e31; A(4,8)=2*e00*e10*e21+2*e00*e11*e20+2*e00*e13*e24+2*e00*e14*e23+2*e00*e16*e27+2*e00*e17*e26+2*e01*e10*e20+6*e01*e11*e21+2*e01*e12*e22-2*e01*e13*e23+2*e01*e14*e24-2*e01*e15*e25-2*e01*e16*e26+2*e01*e17*e27-2*e01*e18*e28+2*e02*e11*e22+2*e02*e12*e21+2*e02*e14*e25+2*e02*e15*e24+2*e02*e17*e28+2*e02*e18*e27+2*e03*e10*e24-2*e03*e11*e23-2*e03*e13*e21+2*e03*e14*e20+2*e04*e10*e23+2*e04*e11*e24+2*e04*e12*e25+2*e04*e13*e20+2*e04*e14*e21+2*e04*e15*e22-2*e05*e11*e25+2*e05*e12*e24+2*e05*e14*e22-2*e05*e15*e21+2*e06*e10*e27-2*e06*e11*e26-2*e06*e16*e21+2*e06*e17*e20+2*e07*e10*e26+2*e07*e11*e27+2*e07*e12*e28+2*e07*e16*e20+2*e07*e17*e21+2*e07*e18*e22-2*e08*e11*e28+2*e08*e12*e27+2*e08*e17*e22-2*e08*e18*e21; A(4,9)=2*e00*e10*e31+2*e00*e11*e30+2*e00*e13*e34+2*e00*e14*e33+2*e00*e16*e37+2*e00*e17*e36+2*e01*e10*e30+6*e01*e11*e31+2*e01*e12*e32-2*e01*e13*e33+2*e01*e14*e34-2*e01*e15*e35-2*e01*e16*e36+2*e01*e17*e37-2*e01*e18*e38+2*e02*e11*e32+2*e02*e12*e31+2*e02*e14*e35+2*e02*e15*e34+2*e02*e17*e38+2*e02*e18*e37+2*e03*e10*e34-2*e03*e11*e33-2*e03*e13*e31+2*e03*e14*e30+2*e04*e10*e33+2*e04*e11*e34+2*e04*e12*e35+2*e04*e13*e30+2*e04*e14*e31+2*e04*e15*e32-2*e05*e11*e35+2*e05*e12*e34+2*e05*e14*e32-2*e05*e15*e31+2*e06*e10*e37-2*e06*e11*e36-2*e06*e16*e31+2*e06*e17*e30+2*e07*e10*e36+2*e07*e11*e37+2*e07*e12*e38+2*e07*e16*e30+2*e07*e17*e31+2*e07*e18*e32-2*e08*e11*e38+2*e08*e12*e37+2*e08*e17*e32-2*e08*e18*e31; A(4,10)=2*e00*e20*e21+2*e00*e23*e24+2*e00*e26*e27+e01*e202+3*e01*e212+e01*e222-e01*e232+e01*e242-e01*e252-e01*e262+e01*e272-e01*e282+2*e02*e21*e22+2*e02*e24*e25+2*e02*e27*e28+2*e03*e20*e24-2*e03*e21*e23+2*e04*e20*e23+2*e04*e21*e24+2*e04*e22*e25-2*e05*e21*e25+2*e05*e22*e24+2*e06*e20*e27-2*e06*e21*e26+2*e07*e20*e26+2*e07*e21*e27+2*e07*e22*e28-2*e08*e21*e28+2*e08*e22*e27; A(4,11)=2*e00*e20*e31+2*e00*e21*e30+2*e00*e23*e34+2*e00*e24*e33+2*e00*e26*e37+2*e00*e27*e36+2*e01*e20*e30+6*e01*e21*e31+2*e01*e22*e32-2*e01*e23*e33+2*e01*e24*e34-2*e01*e25*e35-2*e01*e26*e36+2*e01*e27*e37-2*e01*e28*e38+2*e02*e21*e32+2*e02*e22*e31+2*e02*e24*e35+2*e02*e25*e34+2*e02*e27*e38+2*e02*e28*e37+2*e03*e20*e34-2*e03*e21*e33-2*e03*e23*e31+2*e03*e24*e30+2*e04*e20*e33+2*e04*e21*e34+2*e04*e22*e35+2*e04*e23*e30+2*e04*e24*e31+2*e04*e25*e32-2*e05*e21*e35+2*e05*e22*e34+2*e05*e24*e32-2*e05*e25*e31+2*e06*e20*e37-2*e06*e21*e36-2*e06*e26*e31+2*e06*e27*e30+2*e07*e20*e36+2*e07*e21*e37+2*e07*e22*e38+2*e07*e26*e30+2*e07*e27*e31+2*e07*e28*e32-2*e08*e21*e38+2*e08*e22*e37+2*e08*e27*e32-2*e08*e28*e31; A(4,12)=2*e00*e30*e31+2*e00*e33*e34+2*e00*e36*e37+e01*e302+3*e01*e312+e01*e322-e01*e332+e01*e342-e01*e352-e01*e362+e01*e372-e01*e382+2*e02*e31*e32+2*e02*e34*e35+2*e02*e37*e38+2*e03*e30*e34-2*e03*e31*e33+2*e04*e30*e33+2*e04*e31*e34+2*e04*e32*e35-2*e05*e31*e35+2*e05*e32*e34+2*e06*e30*e37-2*e06*e31*e36+2*e07*e30*e36+2*e07*e31*e37+2*e07*e32*e38-2*e08*e31*e38+2*e08*e32*e37; A(4,13)=2*e10*e20*e21+2*e10*e23*e24+2*e10*e26*e27+e11*e202+3*e11*e212+e11*e222-e11*e232+e11*e242-e11*e252-e11*e262+e11*e272-e11*e282+2*e12*e21*e22+2*e12*e24*e25+2*e12*e27*e28+2*e13*e20*e24-2*e13*e21*e23+2*e14*e20*e23+2*e14*e21*e24+2*e14*e22*e25-2*e15*e21*e25+2*e15*e22*e24+2*e16*e20*e27-2*e16*e21*e26+2*e17*e20*e26+2*e17*e21*e27+2*e17*e22*e28-2*e18*e21*e28+2*e18*e22*e27; A(4,14)=2*e10*e20*e31+2*e10*e21*e30+2*e10*e23*e34+2*e10*e24*e33+2*e10*e26*e37+2*e10*e27*e36+2*e11*e20*e30+6*e11*e21*e31+2*e11*e22*e32-2*e11*e23*e33+2*e11*e24*e34-2*e11*e25*e35-2*e11*e26*e36+2*e11*e27*e37-2*e11*e28*e38+2*e12*e21*e32+2*e12*e22*e31+2*e12*e24*e35+2*e12*e25*e34+2*e12*e27*e38+2*e12*e28*e37+2*e13*e20*e34-2*e13*e21*e33-2*e13*e23*e31+2*e13*e24*e30+2*e14*e20*e33+2*e14*e21*e34+2*e14*e22*e35+2*e14*e23*e30+2*e14*e24*e31+2*e14*e25*e32-2*e15*e21*e35+2*e15*e22*e34+2*e15*e24*e32-2*e15*e25*e31+2*e16*e20*e37-2*e16*e21*e36-2*e16*e26*e31+2*e16*e27*e30+2*e17*e20*e36+2*e17*e21*e37+2*e17*e22*e38+2*e17*e26*e30+2*e17*e27*e31+2*e17*e28*e32-2*e18*e21*e38+2*e18*e22*e37+2*e18*e27*e32-2*e18*e28*e31; A(4,15)=2*e10*e30*e31+2*e10*e33*e34+2*e10*e36*e37+e11*e302+3*e11*e312+e11*e322-e11*e332+e11*e342-e11*e352-e11*e362+e11*e372-e11*e382+2*e12*e31*e32+2*e12*e34*e35+2*e12*e37*e38+2*e13*e30*e34-2*e13*e31*e33+2*e14*e30*e33+2*e14*e31*e34+2*e14*e32*e35-2*e15*e31*e35+2*e15*e32*e34+2*e16*e30*e37-2*e16*e31*e36+2*e17*e30*e36+2*e17*e31*e37+2*e17*e32*e38-2*e18*e31*e38+2*e18*e32*e37; A(4,16)=e202*e21+2*e20*e23*e24+2*e20*e26*e27+e213+e21*e222-e21*e232+e21*e242-e21*e252-e21*e262+e21*e272-e21*e282+2*e22*e24*e25+2*e22*e27*e28; A(4,17)=e202*e31+2*e20*e21*e30+2*e20*e23*e34+2*e20*e24*e33+2*e20*e26*e37+2*e20*e27*e36+3*e212*e31+2*e21*e22*e32-2*e21*e23*e33+2*e21*e24*e34-2*e21*e25*e35-2*e21*e26*e36+2*e21*e27*e37-2*e21*e28*e38+e222*e31+2*e22*e24*e35+2*e22*e25*e34+2*e22*e27*e38+2*e22*e28*e37-e232*e31+2*e23*e24*e30+e242*e31+2*e24*e25*e32-e252*e31-e262*e31+2*e26*e27*e30+e272*e31+2*e27*e28*e32-e282*e31; A(4,18)=2*e20*e30*e31+2*e20*e33*e34+2*e20*e36*e37+e21*e302+3*e21*e312+e21*e322-e21*e332+e21*e342-e21*e352-e21*e362+e21*e372-e21*e382+2*e22*e31*e32+2*e22*e34*e35+2*e22*e37*e38+2*e23*e30*e34-2*e23*e31*e33+2*e24*e30*e33+2*e24*e31*e34+2*e24*e32*e35-2*e25*e31*e35+2*e25*e32*e34+2*e26*e30*e37-2*e26*e31*e36+2*e27*e30*e36+2*e27*e31*e37+2*e27*e32*e38-2*e28*e31*e38+2*e28*e32*e37; A(4,19)=e302*e31+2*e30*e33*e34+2*e30*e36*e37+e313+e31*e322-e31*e332+e31*e342-e31*e352-e31*e362+e31*e372-e31*e382+2*e32*e34*e35+2*e32*e37*e38; A(5,0)=-e002*e04+2*e00*e01*e03+e012*e04+2*e01*e02*e05-e022*e04+e032*e04+2*e03*e06*e07+e043+e04*e052-e04*e062+e04*e072-e04*e082+2*e05*e07*e08; A(5,1)=-e102*e14+2*e10*e11*e13+e112*e14+2*e11*e12*e15-e122*e14+e132*e14+2*e13*e16*e17+e143+e14*e152-e14*e162+e14*e172-e14*e182+2*e15*e17*e18; A(5,2)=-e002*e14+2*e00*e01*e13+2*e00*e03*e11-2*e00*e04*e10+e012*e14+2*e01*e02*e15+2*e01*e03*e10+2*e01*e04*e11+2*e01*e05*e12-e022*e14-2*e02*e04*e12+2*e02*e05*e11+e032*e14+2*e03*e04*e13+2*e03*e06*e17+2*e03*e07*e16+3*e042*e14+2*e04*e05*e15-2*e04*e06*e16+2*e04*e07*e17-2*e04*e08*e18+e052*e14+2*e05*e07*e18+2*e05*e08*e17-e062*e14+2*e06*e07*e13+e072*e14+2*e07*e08*e15-e082*e14; A(5,3)=-2*e00*e10*e14+2*e00*e11*e13+2*e01*e10*e13+2*e01*e11*e14+2*e01*e12*e15+2*e02*e11*e15-2*e02*e12*e14+2*e03*e10*e11+2*e03*e13*e14+2*e03*e16*e17-e04*e102+e04*e112-e04*e122+e04*e132+3*e04*e142+e04*e152-e04*e162+e04*e172-e04*e182+2*e05*e11*e12+2*e05*e14*e15+2*e05*e17*e18+2*e06*e13*e17-2*e06*e14*e16+2*e07*e13*e16+2*e07*e14*e17+2*e07*e15*e18-2*e08*e14*e18+2*e08*e15*e17; A(5,4)=-e002*e24+2*e00*e01*e23+2*e00*e03*e21-2*e00*e04*e20+e012*e24+2*e01*e02*e25+2*e01*e03*e20+2*e01*e04*e21+2*e01*e05*e22-e022*e24-2*e02*e04*e22+2*e02*e05*e21+e032*e24+2*e03*e04*e23+2*e03*e06*e27+2*e03*e07*e26+3*e042*e24+2*e04*e05*e25-2*e04*e06*e26+2*e04*e07*e27-2*e04*e08*e28+e052*e24+2*e05*e07*e28+2*e05*e08*e27-e062*e24+2*e06*e07*e23+e072*e24+2*e07*e08*e25-e082*e24; A(5,5)=-e002*e34+2*e00*e01*e33+2*e00*e03*e31-2*e00*e04*e30+e012*e34+2*e01*e02*e35+2*e01*e03*e30+2*e01*e04*e31+2*e01*e05*e32-e022*e34-2*e02*e04*e32+2*e02*e05*e31+e032*e34+2*e03*e04*e33+2*e03*e06*e37+2*e03*e07*e36+3*e042*e34+2*e04*e05*e35-2*e04*e06*e36+2*e04*e07*e37-2*e04*e08*e38+e052*e34+2*e05*e07*e38+2*e05*e08*e37-e062*e34+2*e06*e07*e33+e072*e34+2*e07*e08*e35-e082*e34; A(5,6)=-e102*e24+2*e10*e11*e23+2*e10*e13*e21-2*e10*e14*e20+e112*e24+2*e11*e12*e25+2*e11*e13*e20+2*e11*e14*e21+2*e11*e15*e22-e122*e24-2*e12*e14*e22+2*e12*e15*e21+e132*e24+2*e13*e14*e23+2*e13*e16*e27+2*e13*e17*e26+3*e142*e24+2*e14*e15*e25-2*e14*e16*e26+2*e14*e17*e27-2*e14*e18*e28+e152*e24+2*e15*e17*e28+2*e15*e18*e27-e162*e24+2*e16*e17*e23+e172*e24+2*e17*e18*e25-e182*e24; A(5,7)=-e102*e34+2*e10*e11*e33+2*e10*e13*e31-2*e10*e14*e30+e112*e34+2*e11*e12*e35+2*e11*e13*e30+2*e11*e14*e31+2*e11*e15*e32-e122*e34-2*e12*e14*e32+2*e12*e15*e31+e132*e34+2*e13*e14*e33+2*e13*e16*e37+2*e13*e17*e36+3*e142*e34+2*e14*e15*e35-2*e14*e16*e36+2*e14*e17*e37-2*e14*e18*e38+e152*e34+2*e15*e17*e38+2*e15*e18*e37-e162*e34+2*e16*e17*e33+e172*e34+2*e17*e18*e35-e182*e34; A(5,8)=-2*e00*e10*e24+2*e00*e11*e23+2*e00*e13*e21-2*e00*e14*e20+2*e01*e10*e23+2*e01*e11*e24+2*e01*e12*e25+2*e01*e13*e20+2*e01*e14*e21+2*e01*e15*e22+2*e02*e11*e25-2*e02*e12*e24-2*e02*e14*e22+2*e02*e15*e21+2*e03*e10*e21+2*e03*e11*e20+2*e03*e13*e24+2*e03*e14*e23+2*e03*e16*e27+2*e03*e17*e26-2*e04*e10*e20+2*e04*e11*e21-2*e04*e12*e22+2*e04*e13*e23+6*e04*e14*e24+2*e04*e15*e25-2*e04*e16*e26+2*e04*e17*e27-2*e04*e18*e28+2*e05*e11*e22+2*e05*e12*e21+2*e05*e14*e25+2*e05*e15*e24+2*e05*e17*e28+2*e05*e18*e27+2*e06*e13*e27-2*e06*e14*e26-2*e06*e16*e24+2*e06*e17*e23+2*e07*e13*e26+2*e07*e14*e27+2*e07*e15*e28+2*e07*e16*e23+2*e07*e17*e24+2*e07*e18*e25-2*e08*e14*e28+2*e08*e15*e27+2*e08*e17*e25-2*e08*e18*e24; A(5,9)=-2*e00*e10*e34+2*e00*e11*e33+2*e00*e13*e31-2*e00*e14*e30+2*e01*e10*e33+2*e01*e11*e34+2*e01*e12*e35+2*e01*e13*e30+2*e01*e14*e31+2*e01*e15*e32+2*e02*e11*e35-2*e02*e12*e34-2*e02*e14*e32+2*e02*e15*e31+2*e03*e10*e31+2*e03*e11*e30+2*e03*e13*e34+2*e03*e14*e33+2*e03*e16*e37+2*e03*e17*e36-2*e04*e10*e30+2*e04*e11*e31-2*e04*e12*e32+2*e04*e13*e33+6*e04*e14*e34+2*e04*e15*e35-2*e04*e16*e36+2*e04*e17*e37-2*e04*e18*e38+2*e05*e11*e32+2*e05*e12*e31+2*e05*e14*e35+2*e05*e15*e34+2*e05*e17*e38+2*e05*e18*e37+2*e06*e13*e37-2*e06*e14*e36-2*e06*e16*e34+2*e06*e17*e33+2*e07*e13*e36+2*e07*e14*e37+2*e07*e15*e38+2*e07*e16*e33+2*e07*e17*e34+2*e07*e18*e35-2*e08*e14*e38+2*e08*e15*e37+2*e08*e17*e35-2*e08*e18*e34; A(5,10)=-2*e00*e20*e24+2*e00*e21*e23+2*e01*e20*e23+2*e01*e21*e24+2*e01*e22*e25+2*e02*e21*e25-2*e02*e22*e24+2*e03*e20*e21+2*e03*e23*e24+2*e03*e26*e27-e04*e202+e04*e212-e04*e222+e04*e232+3*e04*e242+e04*e252-e04*e262+e04*e272-e04*e282+2*e05*e21*e22+2*e05*e24*e25+2*e05*e27*e28+2*e06*e23*e27-2*e06*e24*e26+2*e07*e23*e26+2*e07*e24*e27+2*e07*e25*e28-2*e08*e24*e28+2*e08*e25*e27; A(5,11)=-2*e00*e20*e34+2*e00*e21*e33+2*e00*e23*e31-2*e00*e24*e30+2*e01*e20*e33+2*e01*e21*e34+2*e01*e22*e35+2*e01*e23*e30+2*e01*e24*e31+2*e01*e25*e32+2*e02*e21*e35-2*e02*e22*e34-2*e02*e24*e32+2*e02*e25*e31+2*e03*e20*e31+2*e03*e21*e30+2*e03*e23*e34+2*e03*e24*e33+2*e03*e26*e37+2*e03*e27*e36-2*e04*e20*e30+2*e04*e21*e31-2*e04*e22*e32+2*e04*e23*e33+6*e04*e24*e34+2*e04*e25*e35-2*e04*e26*e36+2*e04*e27*e37-2*e04*e28*e38+2*e05*e21*e32+2*e05*e22*e31+2*e05*e24*e35+2*e05*e25*e34+2*e05*e27*e38+2*e05*e28*e37+2*e06*e23*e37-2*e06*e24*e36-2*e06*e26*e34+2*e06*e27*e33+2*e07*e23*e36+2*e07*e24*e37+2*e07*e25*e38+2*e07*e26*e33+2*e07*e27*e34+2*e07*e28*e35-2*e08*e24*e38+2*e08*e25*e37+2*e08*e27*e35-2*e08*e28*e34; A(5,12)=-2*e00*e30*e34+2*e00*e31*e33+2*e01*e30*e33+2*e01*e31*e34+2*e01*e32*e35+2*e02*e31*e35-2*e02*e32*e34+2*e03*e30*e31+2*e03*e33*e34+2*e03*e36*e37-e04*e302+e04*e312-e04*e322+e04*e332+3*e04*e342+e04*e352-e04*e362+e04*e372-e04*e382+2*e05*e31*e32+2*e05*e34*e35+2*e05*e37*e38+2*e06*e33*e37-2*e06*e34*e36+2*e07*e33*e36+2*e07*e34*e37+2*e07*e35*e38-2*e08*e34*e38+2*e08*e35*e37; A(5,13)=-2*e10*e20*e24+2*e10*e21*e23+2*e11*e20*e23+2*e11*e21*e24+2*e11*e22*e25+2*e12*e21*e25-2*e12*e22*e24+2*e13*e20*e21+2*e13*e23*e24+2*e13*e26*e27-e14*e202+e14*e212-e14*e222+e14*e232+3*e14*e242+e14*e252-e14*e262+e14*e272-e14*e282+2*e15*e21*e22+2*e15*e24*e25+2*e15*e27*e28+2*e16*e23*e27-2*e16*e24*e26+2*e17*e23*e26+2*e17*e24*e27+2*e17*e25*e28-2*e18*e24*e28+2*e18*e25*e27; A(5,14)=-2*e10*e20*e34+2*e10*e21*e33+2*e10*e23*e31-2*e10*e24*e30+2*e11*e20*e33+2*e11*e21*e34+2*e11*e22*e35+2*e11*e23*e30+2*e11*e24*e31+2*e11*e25*e32+2*e12*e21*e35-2*e12*e22*e34-2*e12*e24*e32+2*e12*e25*e31+2*e13*e20*e31+2*e13*e21*e30+2*e13*e23*e34+2*e13*e24*e33+2*e13*e26*e37+2*e13*e27*e36-2*e14*e20*e30+2*e14*e21*e31-2*e14*e22*e32+2*e14*e23*e33+6*e14*e24*e34+2*e14*e25*e35-2*e14*e26*e36+2*e14*e27*e37-2*e14*e28*e38+2*e15*e21*e32+2*e15*e22*e31+2*e15*e24*e35+2*e15*e25*e34+2*e15*e27*e38+2*e15*e28*e37+2*e16*e23*e37-2*e16*e24*e36-2*e16*e26*e34+2*e16*e27*e33+2*e17*e23*e36+2*e17*e24*e37+2*e17*e25*e38+2*e17*e26*e33+2*e17*e27*e34+2*e17*e28*e35-2*e18*e24*e38+2*e18*e25*e37+2*e18*e27*e35-2*e18*e28*e34; A(5,15)=-2*e10*e30*e34+2*e10*e31*e33+2*e11*e30*e33+2*e11*e31*e34+2*e11*e32*e35+2*e12*e31*e35-2*e12*e32*e34+2*e13*e30*e31+2*e13*e33*e34+2*e13*e36*e37-e14*e302+e14*e312-e14*e322+e14*e332+3*e14*e342+e14*e352-e14*e362+e14*e372-e14*e382+2*e15*e31*e32+2*e15*e34*e35+2*e15*e37*e38+2*e16*e33*e37-2*e16*e34*e36+2*e17*e33*e36+2*e17*e34*e37+2*e17*e35*e38-2*e18*e34*e38+2*e18*e35*e37; A(5,16)=-e202*e24+2*e20*e21*e23+e212*e24+2*e21*e22*e25-e222*e24+e232*e24+2*e23*e26*e27+e243+e24*e252-e24*e262+e24*e272-e24*e282+2*e25*e27*e28; A(5,17)=-e202*e34+2*e20*e21*e33+2*e20*e23*e31-2*e20*e24*e30+e212*e34+2*e21*e22*e35+2*e21*e23*e30+2*e21*e24*e31+2*e21*e25*e32-e222*e34-2*e22*e24*e32+2*e22*e25*e31+e232*e34+2*e23*e24*e33+2*e23*e26*e37+2*e23*e27*e36+3*e242*e34+2*e24*e25*e35-2*e24*e26*e36+2*e24*e27*e37-2*e24*e28*e38+e252*e34+2*e25*e27*e38+2*e25*e28*e37-e262*e34+2*e26*e27*e33+e272*e34+2*e27*e28*e35-e282*e34; A(5,18)=-2*e20*e30*e34+2*e20*e31*e33+2*e21*e30*e33+2*e21*e31*e34+2*e21*e32*e35+2*e22*e31*e35-2*e22*e32*e34+2*e23*e30*e31+2*e23*e33*e34+2*e23*e36*e37-e24*e302+e24*e312-e24*e322+e24*e332+3*e24*e342+e24*e352-e24*e362+e24*e372-e24*e382+2*e25*e31*e32+2*e25*e34*e35+2*e25*e37*e38+2*e26*e33*e37-2*e26*e34*e36+2*e27*e33*e36+2*e27*e34*e37+2*e27*e35*e38-2*e28*e34*e38+2*e28*e35*e37; A(5,19)=-e302*e34+2*e30*e31*e33+e312*e34+2*e31*e32*e35-e322*e34+e332*e34+2*e33*e36*e37+e343+e34*e352-e34*e362+e34*e372-e34*e382+2*e35*e37*e38; A(6,0)=-e002*e07+2*e00*e01*e06+e012*e07+2*e01*e02*e08-e022*e07-e032*e07+2*e03*e04*e06+e042*e07+2*e04*e05*e08-e052*e07+e062*e07+e073+e07*e082; A(6,1)=-e102*e17+2*e10*e11*e16+e112*e17+2*e11*e12*e18-e122*e17-e132*e17+2*e13*e14*e16+e142*e17+2*e14*e15*e18-e152*e17+e162*e17+e173+e17*e182; A(6,2)=-e002*e17+2*e00*e01*e16+2*e00*e06*e11-2*e00*e07*e10+e012*e17+2*e01*e02*e18+2*e01*e06*e10+2*e01*e07*e11+2*e01*e08*e12-e022*e17-2*e02*e07*e12+2*e02*e08*e11-e032*e17+2*e03*e04*e16+2*e03*e06*e14-2*e03*e07*e13+e042*e17+2*e04*e05*e18+2*e04*e06*e13+2*e04*e07*e14+2*e04*e08*e15-e052*e17-2*e05*e07*e15+2*e05*e08*e14+e062*e17+2*e06*e07*e16+3*e072*e17+2*e07*e08*e18+e082*e17; A(6,3)=-2*e00*e10*e17+2*e00*e11*e16+2*e01*e10*e16+2*e01*e11*e17+2*e01*e12*e18+2*e02*e11*e18-2*e02*e12*e17-2*e03*e13*e17+2*e03*e14*e16+2*e04*e13*e16+2*e04*e14*e17+2*e04*e15*e18+2*e05*e14*e18-2*e05*e15*e17+2*e06*e10*e11+2*e06*e13*e14+2*e06*e16*e17-e07*e102+e07*e112-e07*e122-e07*e132+e07*e142-e07*e152+e07*e162+3*e07*e172+e07*e182+2*e08*e11*e12+2*e08*e14*e15+2*e08*e17*e18; A(6,4)=-e002*e27+2*e00*e01*e26+2*e00*e06*e21-2*e00*e07*e20+e012*e27+2*e01*e02*e28+2*e01*e06*e20+2*e01*e07*e21+2*e01*e08*e22-e022*e27-2*e02*e07*e22+2*e02*e08*e21-e032*e27+2*e03*e04*e26+2*e03*e06*e24-2*e03*e07*e23+e042*e27+2*e04*e05*e28+2*e04*e06*e23+2*e04*e07*e24+2*e04*e08*e25-e052*e27-2*e05*e07*e25+2*e05*e08*e24+e062*e27+2*e06*e07*e26+3*e072*e27+2*e07*e08*e28+e082*e27; A(6,5)=-e002*e37+2*e00*e01*e36+2*e00*e06*e31-2*e00*e07*e30+e012*e37+2*e01*e02*e38+2*e01*e06*e30+2*e01*e07*e31+2*e01*e08*e32-e022*e37-2*e02*e07*e32+2*e02*e08*e31-e032*e37+2*e03*e04*e36+2*e03*e06*e34-2*e03*e07*e33+e042*e37+2*e04*e05*e38+2*e04*e06*e33+2*e04*e07*e34+2*e04*e08*e35-e052*e37-2*e05*e07*e35+2*e05*e08*e34+e062*e37+2*e06*e07*e36+3*e072*e37+2*e07*e08*e38+e082*e37; A(6,6)=-e102*e27+2*e10*e11*e26+2*e10*e16*e21-2*e10*e17*e20+e112*e27+2*e11*e12*e28+2*e11*e16*e20+2*e11*e17*e21+2*e11*e18*e22-e122*e27-2*e12*e17*e22+2*e12*e18*e21-e132*e27+2*e13*e14*e26+2*e13*e16*e24-2*e13*e17*e23+e142*e27+2*e14*e15*e28+2*e14*e16*e23+2*e14*e17*e24+2*e14*e18*e25-e152*e27-2*e15*e17*e25+2*e15*e18*e24+e162*e27+2*e16*e17*e26+3*e172*e27+2*e17*e18*e28+e182*e27; A(6,7)=-e102*e37+2*e10*e11*e36+2*e10*e16*e31-2*e10*e17*e30+e112*e37+2*e11*e12*e38+2*e11*e16*e30+2*e11*e17*e31+2*e11*e18*e32-e122*e37-2*e12*e17*e32+2*e12*e18*e31-e132*e37+2*e13*e14*e36+2*e13*e16*e34-2*e13*e17*e33+e142*e37+2*e14*e15*e38+2*e14*e16*e33+2*e14*e17*e34+2*e14*e18*e35-e152*e37-2*e15*e17*e35+2*e15*e18*e34+e162*e37+2*e16*e17*e36+3*e172*e37+2*e17*e18*e38+e182*e37; A(6,8)=-2*e00*e10*e27+2*e00*e11*e26+2*e00*e16*e21-2*e00*e17*e20+2*e01*e10*e26+2*e01*e11*e27+2*e01*e12*e28+2*e01*e16*e20+2*e01*e17*e21+2*e01*e18*e22+2*e02*e11*e28-2*e02*e12*e27-2*e02*e17*e22+2*e02*e18*e21-2*e03*e13*e27+2*e03*e14*e26+2*e03*e16*e24-2*e03*e17*e23+2*e04*e13*e26+2*e04*e14*e27+2*e04*e15*e28+2*e04*e16*e23+2*e04*e17*e24+2*e04*e18*e25+2*e05*e14*e28-2*e05*e15*e27-2*e05*e17*e25+2*e05*e18*e24+2*e06*e10*e21+2*e06*e11*e20+2*e06*e13*e24+2*e06*e14*e23+2*e06*e16*e27+2*e06*e17*e26-2*e07*e10*e20+2*e07*e11*e21-2*e07*e12*e22-2*e07*e13*e23+2*e07*e14*e24-2*e07*e15*e25+2*e07*e16*e26+6*e07*e17*e27+2*e07*e18*e28+2*e08*e11*e22+2*e08*e12*e21+2*e08*e14*e25+2*e08*e15*e24+2*e08*e17*e28+2*e08*e18*e27; A(6,9)=-2*e00*e10*e37+2*e00*e11*e36+2*e00*e16*e31-2*e00*e17*e30+2*e01*e10*e36+2*e01*e11*e37+2*e01*e12*e38+2*e01*e16*e30+2*e01*e17*e31+2*e01*e18*e32+2*e02*e11*e38-2*e02*e12*e37-2*e02*e17*e32+2*e02*e18*e31-2*e03*e13*e37+2*e03*e14*e36+2*e03*e16*e34-2*e03*e17*e33+2*e04*e13*e36+2*e04*e14*e37+2*e04*e15*e38+2*e04*e16*e33+2*e04*e17*e34+2*e04*e18*e35+2*e05*e14*e38-2*e05*e15*e37-2*e05*e17*e35+2*e05*e18*e34+2*e06*e10*e31+2*e06*e11*e30+2*e06*e13*e34+2*e06*e14*e33+2*e06*e16*e37+2*e06*e17*e36-2*e07*e10*e30+2*e07*e11*e31-2*e07*e12*e32-2*e07*e13*e33+2*e07*e14*e34-2*e07*e15*e35+2*e07*e16*e36+6*e07*e17*e37+2*e07*e18*e38+2*e08*e11*e32+2*e08*e12*e31+2*e08*e14*e35+2*e08*e15*e34+2*e08*e17*e38+2*e08*e18*e37; A(6,10)=-2*e00*e20*e27+2*e00*e21*e26+2*e01*e20*e26+2*e01*e21*e27+2*e01*e22*e28+2*e02*e21*e28-2*e02*e22*e27-2*e03*e23*e27+2*e03*e24*e26+2*e04*e23*e26+2*e04*e24*e27+2*e04*e25*e28+2*e05*e24*e28-2*e05*e25*e27+2*e06*e20*e21+2*e06*e23*e24+2*e06*e26*e27-e07*e202+e07*e212-e07*e222-e07*e232+e07*e242-e07*e252+e07*e262+3*e07*e272+e07*e282+2*e08*e21*e22+2*e08*e24*e25+2*e08*e27*e28; A(6,11)=-2*e00*e20*e37+2*e00*e21*e36+2*e00*e26*e31-2*e00*e27*e30+2*e01*e20*e36+2*e01*e21*e37+2*e01*e22*e38+2*e01*e26*e30+2*e01*e27*e31+2*e01*e28*e32+2*e02*e21*e38-2*e02*e22*e37-2*e02*e27*e32+2*e02*e28*e31-2*e03*e23*e37+2*e03*e24*e36+2*e03*e26*e34-2*e03*e27*e33+2*e04*e23*e36+2*e04*e24*e37+2*e04*e25*e38+2*e04*e26*e33+2*e04*e27*e34+2*e04*e28*e35+2*e05*e24*e38-2*e05*e25*e37-2*e05*e27*e35+2*e05*e28*e34+2*e06*e20*e31+2*e06*e21*e30+2*e06*e23*e34+2*e06*e24*e33+2*e06*e26*e37+2*e06*e27*e36-2*e07*e20*e30+2*e07*e21*e31-2*e07*e22*e32-2*e07*e23*e33+2*e07*e24*e34-2*e07*e25*e35+2*e07*e26*e36+6*e07*e27*e37+2*e07*e28*e38+2*e08*e21*e32+2*e08*e22*e31+2*e08*e24*e35+2*e08*e25*e34+2*e08*e27*e38+2*e08*e28*e37; A(6,12)=-2*e00*e30*e37+2*e00*e31*e36+2*e01*e30*e36+2*e01*e31*e37+2*e01*e32*e38+2*e02*e31*e38-2*e02*e32*e37-2*e03*e33*e37+2*e03*e34*e36+2*e04*e33*e36+2*e04*e34*e37+2*e04*e35*e38+2*e05*e34*e38-2*e05*e35*e37+2*e06*e30*e31+2*e06*e33*e34+2*e06*e36*e37-e07*e302+e07*e312-e07*e322-e07*e332+e07*e342-e07*e352+e07*e362+3*e07*e372+e07*e382+2*e08*e31*e32+2*e08*e34*e35+2*e08*e37*e38; A(6,13)=-2*e10*e20*e27+2*e10*e21*e26+2*e11*e20*e26+2*e11*e21*e27+2*e11*e22*e28+2*e12*e21*e28-2*e12*e22*e27-2*e13*e23*e27+2*e13*e24*e26+2*e14*e23*e26+2*e14*e24*e27+2*e14*e25*e28+2*e15*e24*e28-2*e15*e25*e27+2*e16*e20*e21+2*e16*e23*e24+2*e16*e26*e27-e17*e202+e17*e212-e17*e222-e17*e232+e17*e242-e17*e252+e17*e262+3*e17*e272+e17*e282+2*e18*e21*e22+2*e18*e24*e25+2*e18*e27*e28; A(6,14)=-2*e10*e20*e37+2*e10*e21*e36+2*e10*e26*e31-2*e10*e27*e30+2*e11*e20*e36+2*e11*e21*e37+2*e11*e22*e38+2*e11*e26*e30+2*e11*e27*e31+2*e11*e28*e32+2*e12*e21*e38-2*e12*e22*e37-2*e12*e27*e32+2*e12*e28*e31-2*e13*e23*e37+2*e13*e24*e36+2*e13*e26*e34-2*e13*e27*e33+2*e14*e23*e36+2*e14*e24*e37+2*e14*e25*e38+2*e14*e26*e33+2*e14*e27*e34+2*e14*e28*e35+2*e15*e24*e38-2*e15*e25*e37-2*e15*e27*e35+2*e15*e28*e34+2*e16*e20*e31+2*e16*e21*e30+2*e16*e23*e34+2*e16*e24*e33+2*e16*e26*e37+2*e16*e27*e36-2*e17*e20*e30+2*e17*e21*e31-2*e17*e22*e32-2*e17*e23*e33+2*e17*e24*e34-2*e17*e25*e35+2*e17*e26*e36+6*e17*e27*e37+2*e17*e28*e38+2*e18*e21*e32+2*e18*e22*e31+2*e18*e24*e35+2*e18*e25*e34+2*e18*e27*e38+2*e18*e28*e37; A(6,15)=-2*e10*e30*e37+2*e10*e31*e36+2*e11*e30*e36+2*e11*e31*e37+2*e11*e32*e38+2*e12*e31*e38-2*e12*e32*e37-2*e13*e33*e37+2*e13*e34*e36+2*e14*e33*e36+2*e14*e34*e37+2*e14*e35*e38+2*e15*e34*e38-2*e15*e35*e37+2*e16*e30*e31+2*e16*e33*e34+2*e16*e36*e37-e17*e302+e17*e312-e17*e322-e17*e332+e17*e342-e17*e352+e17*e362+3*e17*e372+e17*e382+2*e18*e31*e32+2*e18*e34*e35+2*e18*e37*e38; A(6,16)=-e202*e27+2*e20*e21*e26+e212*e27+2*e21*e22*e28-e222*e27-e232*e27+2*e23*e24*e26+e242*e27+2*e24*e25*e28-e252*e27+e262*e27+e273+e27*e282; A(6,17)=-e202*e37+2*e20*e21*e36+2*e20*e26*e31-2*e20*e27*e30+e212*e37+2*e21*e22*e38+2*e21*e26*e30+2*e21*e27*e31+2*e21*e28*e32-e222*e37-2*e22*e27*e32+2*e22*e28*e31-e232*e37+2*e23*e24*e36+2*e23*e26*e34-2*e23*e27*e33+e242*e37+2*e24*e25*e38+2*e24*e26*e33+2*e24*e27*e34+2*e24*e28*e35-e252*e37-2*e25*e27*e35+2*e25*e28*e34+e262*e37+2*e26*e27*e36+3*e272*e37+2*e27*e28*e38+e282*e37; A(6,18)=-2*e20*e30*e37+2*e20*e31*e36+2*e21*e30*e36+2*e21*e31*e37+2*e21*e32*e38+2*e22*e31*e38-2*e22*e32*e37-2*e23*e33*e37+2*e23*e34*e36+2*e24*e33*e36+2*e24*e34*e37+2*e24*e35*e38+2*e25*e34*e38-2*e25*e35*e37+2*e26*e30*e31+2*e26*e33*e34+2*e26*e36*e37-e27*e302+e27*e312-e27*e322-e27*e332+e27*e342-e27*e352+e27*e362+3*e27*e372+e27*e382+2*e28*e31*e32+2*e28*e34*e35+2*e28*e37*e38; A(6,19)=-e302*e37+2*e30*e31*e36+e312*e37+2*e31*e32*e38-e322*e37-e332*e37+2*e33*e34*e36+e342*e37+2*e34*e35*e38-e352*e37+e362*e37+e373+e37*e382; A(7,0)=e002*e02+2*e00*e03*e05+2*e00*e06*e08+e012*e02+2*e01*e04*e05+2*e01*e07*e08+e023-e02*e032-e02*e042+e02*e052-e02*e062-e02*e072+e02*e082; A(7,1)=e102*e12+2*e10*e13*e15+2*e10*e16*e18+e112*e12+2*e11*e14*e15+2*e11*e17*e18+e123-e12*e132-e12*e142+e12*e152-e12*e162-e12*e172+e12*e182; A(7,2)=e002*e12+2*e00*e02*e10+2*e00*e03*e15+2*e00*e05*e13+2*e00*e06*e18+2*e00*e08*e16+e012*e12+2*e01*e02*e11+2*e01*e04*e15+2*e01*e05*e14+2*e01*e07*e18+2*e01*e08*e17+3*e022*e12-2*e02*e03*e13-2*e02*e04*e14+2*e02*e05*e15-2*e02*e06*e16-2*e02*e07*e17+2*e02*e08*e18-e032*e12+2*e03*e05*e10-e042*e12+2*e04*e05*e11+e052*e12-e062*e12+2*e06*e08*e10-e072*e12+2*e07*e08*e11+e082*e12; A(7,3)=2*e00*e10*e12+2*e00*e13*e15+2*e00*e16*e18+2*e01*e11*e12+2*e01*e14*e15+2*e01*e17*e18+e02*e102+e02*e112+3*e02*e122-e02*e132-e02*e142+e02*e152-e02*e162-e02*e172+e02*e182+2*e03*e10*e15-2*e03*e12*e13+2*e04*e11*e15-2*e04*e12*e14+2*e05*e10*e13+2*e05*e11*e14+2*e05*e12*e15+2*e06*e10*e18-2*e06*e12*e16+2*e07*e11*e18-2*e07*e12*e17+2*e08*e10*e16+2*e08*e11*e17+2*e08*e12*e18; A(7,4)=e002*e22+2*e00*e02*e20+2*e00*e03*e25+2*e00*e05*e23+2*e00*e06*e28+2*e00*e08*e26+e012*e22+2*e01*e02*e21+2*e01*e04*e25+2*e01*e05*e24+2*e01*e07*e28+2*e01*e08*e27+3*e022*e22-2*e02*e03*e23-2*e02*e04*e24+2*e02*e05*e25-2*e02*e06*e26-2*e02*e07*e27+2*e02*e08*e28-e032*e22+2*e03*e05*e20-e042*e22+2*e04*e05*e21+e052*e22-e062*e22+2*e06*e08*e20-e072*e22+2*e07*e08*e21+e082*e22; A(7,5)=e002*e32+2*e00*e02*e30+2*e00*e03*e35+2*e00*e05*e33+2*e00*e06*e38+2*e00*e08*e36+e012*e32+2*e01*e02*e31+2*e01*e04*e35+2*e01*e05*e34+2*e01*e07*e38+2*e01*e08*e37+3*e022*e32-2*e02*e03*e33-2*e02*e04*e34+2*e02*e05*e35-2*e02*e06*e36-2*e02*e07*e37+2*e02*e08*e38-e032*e32+2*e03*e05*e30-e042*e32+2*e04*e05*e31+e052*e32-e062*e32+2*e06*e08*e30-e072*e32+2*e07*e08*e31+e082*e32; A(7,6)=e102*e22+2*e10*e12*e20+2*e10*e13*e25+2*e10*e15*e23+2*e10*e16*e28+2*e10*e18*e26+e112*e22+2*e11*e12*e21+2*e11*e14*e25+2*e11*e15*e24+2*e11*e17*e28+2*e11*e18*e27+3*e122*e22-2*e12*e13*e23-2*e12*e14*e24+2*e12*e15*e25-2*e12*e16*e26-2*e12*e17*e27+2*e12*e18*e28-e132*e22+2*e13*e15*e20-e142*e22+2*e14*e15*e21+e152*e22-e162*e22+2*e16*e18*e20-e172*e22+2*e17*e18*e21+e182*e22; A(7,7)=e102*e32+2*e10*e12*e30+2*e10*e13*e35+2*e10*e15*e33+2*e10*e16*e38+2*e10*e18*e36+e112*e32+2*e11*e12*e31+2*e11*e14*e35+2*e11*e15*e34+2*e11*e17*e38+2*e11*e18*e37+3*e122*e32-2*e12*e13*e33-2*e12*e14*e34+2*e12*e15*e35-2*e12*e16*e36-2*e12*e17*e37+2*e12*e18*e38-e132*e32+2*e13*e15*e30-e142*e32+2*e14*e15*e31+e152*e32-e162*e32+2*e16*e18*e30-e172*e32+2*e17*e18*e31+e182*e32; A(7,8)=2*e00*e10*e22+2*e00*e12*e20+2*e00*e13*e25+2*e00*e15*e23+2*e00*e16*e28+2*e00*e18*e26+2*e01*e11*e22+2*e01*e12*e21+2*e01*e14*e25+2*e01*e15*e24+2*e01*e17*e28+2*e01*e18*e27+2*e02*e10*e20+2*e02*e11*e21+6*e02*e12*e22-2*e02*e13*e23-2*e02*e14*e24+2*e02*e15*e25-2*e02*e16*e26-2*e02*e17*e27+2*e02*e18*e28+2*e03*e10*e25-2*e03*e12*e23-2*e03*e13*e22+2*e03*e15*e20+2*e04*e11*e25-2*e04*e12*e24-2*e04*e14*e22+2*e04*e15*e21+2*e05*e10*e23+2*e05*e11*e24+2*e05*e12*e25+2*e05*e13*e20+2*e05*e14*e21+2*e05*e15*e22+2*e06*e10*e28-2*e06*e12*e26-2*e06*e16*e22+2*e06*e18*e20+2*e07*e11*e28-2*e07*e12*e27-2*e07*e17*e22+2*e07*e18*e21+2*e08*e10*e26+2*e08*e11*e27+2*e08*e12*e28+2*e08*e16*e20+2*e08*e17*e21+2*e08*e18*e22; A(7,9)=2*e00*e10*e32+2*e00*e12*e30+2*e00*e13*e35+2*e00*e15*e33+2*e00*e16*e38+2*e00*e18*e36+2*e01*e11*e32+2*e01*e12*e31+2*e01*e14*e35+2*e01*e15*e34+2*e01*e17*e38+2*e01*e18*e37+2*e02*e10*e30+2*e02*e11*e31+6*e02*e12*e32-2*e02*e13*e33-2*e02*e14*e34+2*e02*e15*e35-2*e02*e16*e36-2*e02*e17*e37+2*e02*e18*e38+2*e03*e10*e35-2*e03*e12*e33-2*e03*e13*e32+2*e03*e15*e30+2*e04*e11*e35-2*e04*e12*e34-2*e04*e14*e32+2*e04*e15*e31+2*e05*e10*e33+2*e05*e11*e34+2*e05*e12*e35+2*e05*e13*e30+2*e05*e14*e31+2*e05*e15*e32+2*e06*e10*e38-2*e06*e12*e36-2*e06*e16*e32+2*e06*e18*e30+2*e07*e11*e38-2*e07*e12*e37-2*e07*e17*e32+2*e07*e18*e31+2*e08*e10*e36+2*e08*e11*e37+2*e08*e12*e38+2*e08*e16*e30+2*e08*e17*e31+2*e08*e18*e32; A(7,10)=2*e00*e20*e22+2*e00*e23*e25+2*e00*e26*e28+2*e01*e21*e22+2*e01*e24*e25+2*e01*e27*e28+e02*e202+e02*e212+3*e02*e222-e02*e232-e02*e242+e02*e252-e02*e262-e02*e272+e02*e282+2*e03*e20*e25-2*e03*e22*e23+2*e04*e21*e25-2*e04*e22*e24+2*e05*e20*e23+2*e05*e21*e24+2*e05*e22*e25+2*e06*e20*e28-2*e06*e22*e26+2*e07*e21*e28-2*e07*e22*e27+2*e08*e20*e26+2*e08*e21*e27+2*e08*e22*e28; A(7,11)=2*e00*e20*e32+2*e00*e22*e30+2*e00*e23*e35+2*e00*e25*e33+2*e00*e26*e38+2*e00*e28*e36+2*e01*e21*e32+2*e01*e22*e31+2*e01*e24*e35+2*e01*e25*e34+2*e01*e27*e38+2*e01*e28*e37+2*e02*e20*e30+2*e02*e21*e31+6*e02*e22*e32-2*e02*e23*e33-2*e02*e24*e34+2*e02*e25*e35-2*e02*e26*e36-2*e02*e27*e37+2*e02*e28*e38+2*e03*e20*e35-2*e03*e22*e33-2*e03*e23*e32+2*e03*e25*e30+2*e04*e21*e35-2*e04*e22*e34-2*e04*e24*e32+2*e04*e25*e31+2*e05*e20*e33+2*e05*e21*e34+2*e05*e22*e35+2*e05*e23*e30+2*e05*e24*e31+2*e05*e25*e32+2*e06*e20*e38-2*e06*e22*e36-2*e06*e26*e32+2*e06*e28*e30+2*e07*e21*e38-2*e07*e22*e37-2*e07*e27*e32+2*e07*e28*e31+2*e08*e20*e36+2*e08*e21*e37+2*e08*e22*e38+2*e08*e26*e30+2*e08*e27*e31+2*e08*e28*e32; A(7,12)=2*e00*e30*e32+2*e00*e33*e35+2*e00*e36*e38+2*e01*e31*e32+2*e01*e34*e35+2*e01*e37*e38+e02*e302+e02*e312+3*e02*e322-e02*e332-e02*e342+e02*e352-e02*e362-e02*e372+e02*e382+2*e03*e30*e35-2*e03*e32*e33+2*e04*e31*e35-2*e04*e32*e34+2*e05*e30*e33+2*e05*e31*e34+2*e05*e32*e35+2*e06*e30*e38-2*e06*e32*e36+2*e07*e31*e38-2*e07*e32*e37+2*e08*e30*e36+2*e08*e31*e37+2*e08*e32*e38; A(7,13)=2*e10*e20*e22+2*e10*e23*e25+2*e10*e26*e28+2*e11*e21*e22+2*e11*e24*e25+2*e11*e27*e28+e12*e202+e12*e212+3*e12*e222-e12*e232-e12*e242+e12*e252-e12*e262-e12*e272+e12*e282+2*e13*e20*e25-2*e13*e22*e23+2*e14*e21*e25-2*e14*e22*e24+2*e15*e20*e23+2*e15*e21*e24+2*e15*e22*e25+2*e16*e20*e28-2*e16*e22*e26+2*e17*e21*e28-2*e17*e22*e27+2*e18*e20*e26+2*e18*e21*e27+2*e18*e22*e28; A(7,14)=2*e10*e20*e32+2*e10*e22*e30+2*e10*e23*e35+2*e10*e25*e33+2*e10*e26*e38+2*e10*e28*e36+2*e11*e21*e32+2*e11*e22*e31+2*e11*e24*e35+2*e11*e25*e34+2*e11*e27*e38+2*e11*e28*e37+2*e12*e20*e30+2*e12*e21*e31+6*e12*e22*e32-2*e12*e23*e33-2*e12*e24*e34+2*e12*e25*e35-2*e12*e26*e36-2*e12*e27*e37+2*e12*e28*e38+2*e13*e20*e35-2*e13*e22*e33-2*e13*e23*e32+2*e13*e25*e30+2*e14*e21*e35-2*e14*e22*e34-2*e14*e24*e32+2*e14*e25*e31+2*e15*e20*e33+2*e15*e21*e34+2*e15*e22*e35+2*e15*e23*e30+2*e15*e24*e31+2*e15*e25*e32+2*e16*e20*e38-2*e16*e22*e36-2*e16*e26*e32+2*e16*e28*e30+2*e17*e21*e38-2*e17*e22*e37-2*e17*e27*e32+2*e17*e28*e31+2*e18*e20*e36+2*e18*e21*e37+2*e18*e22*e38+2*e18*e26*e30+2*e18*e27*e31+2*e18*e28*e32; A(7,15)=2*e10*e30*e32+2*e10*e33*e35+2*e10*e36*e38+2*e11*e31*e32+2*e11*e34*e35+2*e11*e37*e38+e12*e302+e12*e312+3*e12*e322-e12*e332-e12*e342+e12*e352-e12*e362-e12*e372+e12*e382+2*e13*e30*e35-2*e13*e32*e33+2*e14*e31*e35-2*e14*e32*e34+2*e15*e30*e33+2*e15*e31*e34+2*e15*e32*e35+2*e16*e30*e38-2*e16*e32*e36+2*e17*e31*e38-2*e17*e32*e37+2*e18*e30*e36+2*e18*e31*e37+2*e18*e32*e38; A(7,16)=e202*e22+2*e20*e23*e25+2*e20*e26*e28+e212*e22+2*e21*e24*e25+2*e21*e27*e28+e223-e22*e232-e22*e242+e22*e252-e22*e262-e22*e272+e22*e282; A(7,17)=e202*e32+2*e20*e22*e30+2*e20*e23*e35+2*e20*e25*e33+2*e20*e26*e38+2*e20*e28*e36+e212*e32+2*e21*e22*e31+2*e21*e24*e35+2*e21*e25*e34+2*e21*e27*e38+2*e21*e28*e37+3*e222*e32-2*e22*e23*e33-2*e22*e24*e34+2*e22*e25*e35-2*e22*e26*e36-2*e22*e27*e37+2*e22*e28*e38-e232*e32+2*e23*e25*e30-e242*e32+2*e24*e25*e31+e252*e32-e262*e32+2*e26*e28*e30-e272*e32+2*e27*e28*e31+e282*e32; A(7,18)=2*e20*e30*e32+2*e20*e33*e35+2*e20*e36*e38+2*e21*e31*e32+2*e21*e34*e35+2*e21*e37*e38+e22*e302+e22*e312+3*e22*e322-e22*e332-e22*e342+e22*e352-e22*e362-e22*e372+e22*e382+2*e23*e30*e35-2*e23*e32*e33+2*e24*e31*e35-2*e24*e32*e34+2*e25*e30*e33+2*e25*e31*e34+2*e25*e32*e35+2*e26*e30*e38-2*e26*e32*e36+2*e27*e31*e38-2*e27*e32*e37+2*e28*e30*e36+2*e28*e31*e37+2*e28*e32*e38; A(7,19)=e302*e32+2*e30*e33*e35+2*e30*e36*e38+e312*e32+2*e31*e34*e35+2*e31*e37*e38+e323-e32*e332-e32*e342+e32*e352-e32*e362-e32*e372+e32*e382; A(8,0)=-e002*e05+2*e00*e02*e03-e012*e05+2*e01*e02*e04+e022*e05+e032*e05+2*e03*e06*e08+e042*e05+2*e04*e07*e08+e053-e05*e062-e05*e072+e05*e082; A(8,1)=-e102*e15+2*e10*e12*e13-e112*e15+2*e11*e12*e14+e122*e15+e132*e15+2*e13*e16*e18+e142*e15+2*e14*e17*e18+e153-e15*e162-e15*e172+e15*e182; A(8,2)=-e002*e15+2*e00*e02*e13+2*e00*e03*e12-2*e00*e05*e10-e012*e15+2*e01*e02*e14+2*e01*e04*e12-2*e01*e05*e11+e022*e15+2*e02*e03*e10+2*e02*e04*e11+2*e02*e05*e12+e032*e15+2*e03*e05*e13+2*e03*e06*e18+2*e03*e08*e16+e042*e15+2*e04*e05*e14+2*e04*e07*e18+2*e04*e08*e17+3*e052*e15-2*e05*e06*e16-2*e05*e07*e17+2*e05*e08*e18-e062*e15+2*e06*e08*e13-e072*e15+2*e07*e08*e14+e082*e15; A(8,3)=-2*e00*e10*e15+2*e00*e12*e13-2*e01*e11*e15+2*e01*e12*e14+2*e02*e10*e13+2*e02*e11*e14+2*e02*e12*e15+2*e03*e10*e12+2*e03*e13*e15+2*e03*e16*e18+2*e04*e11*e12+2*e04*e14*e15+2*e04*e17*e18-e05*e102-e05*e112+e05*e122+e05*e132+e05*e142+3*e05*e152-e05*e162-e05*e172+e05*e182+2*e06*e13*e18-2*e06*e15*e16+2*e07*e14*e18-2*e07*e15*e17+2*e08*e13*e16+2*e08*e14*e17+2*e08*e15*e18; A(8,4)=-e002*e25+2*e00*e02*e23+2*e00*e03*e22-2*e00*e05*e20-e012*e25+2*e01*e02*e24+2*e01*e04*e22-2*e01*e05*e21+e022*e25+2*e02*e03*e20+2*e02*e04*e21+2*e02*e05*e22+e032*e25+2*e03*e05*e23+2*e03*e06*e28+2*e03*e08*e26+e042*e25+2*e04*e05*e24+2*e04*e07*e28+2*e04*e08*e27+3*e052*e25-2*e05*e06*e26-2*e05*e07*e27+2*e05*e08*e28-e062*e25+2*e06*e08*e23-e072*e25+2*e07*e08*e24+e082*e25; A(8,5)=-e002*e35+2*e00*e02*e33+2*e00*e03*e32-2*e00*e05*e30-e012*e35+2*e01*e02*e34+2*e01*e04*e32-2*e01*e05*e31+e022*e35+2*e02*e03*e30+2*e02*e04*e31+2*e02*e05*e32+e032*e35+2*e03*e05*e33+2*e03*e06*e38+2*e03*e08*e36+e042*e35+2*e04*e05*e34+2*e04*e07*e38+2*e04*e08*e37+3*e052*e35-2*e05*e06*e36-2*e05*e07*e37+2*e05*e08*e38-e062*e35+2*e06*e08*e33-e072*e35+2*e07*e08*e34+e082*e35; A(8,6)=-e102*e25+2*e10*e12*e23+2*e10*e13*e22-2*e10*e15*e20-e112*e25+2*e11*e12*e24+2*e11*e14*e22-2*e11*e15*e21+e122*e25+2*e12*e13*e20+2*e12*e14*e21+2*e12*e15*e22+e132*e25+2*e13*e15*e23+2*e13*e16*e28+2*e13*e18*e26+e142*e25+2*e14*e15*e24+2*e14*e17*e28+2*e14*e18*e27+3*e152*e25-2*e15*e16*e26-2*e15*e17*e27+2*e15*e18*e28-e162*e25+2*e16*e18*e23-e172*e25+2*e17*e18*e24+e182*e25; A(8,7)=-e102*e35+2*e10*e12*e33+2*e10*e13*e32-2*e10*e15*e30-e112*e35+2*e11*e12*e34+2*e11*e14*e32-2*e11*e15*e31+e122*e35+2*e12*e13*e30+2*e12*e14*e31+2*e12*e15*e32+e132*e35+2*e13*e15*e33+2*e13*e16*e38+2*e13*e18*e36+e142*e35+2*e14*e15*e34+2*e14*e17*e38+2*e14*e18*e37+3*e152*e35-2*e15*e16*e36-2*e15*e17*e37+2*e15*e18*e38-e162*e35+2*e16*e18*e33-e172*e35+2*e17*e18*e34+e182*e35; A(8,8)=-2*e00*e10*e25+2*e00*e12*e23+2*e00*e13*e22-2*e00*e15*e20-2*e01*e11*e25+2*e01*e12*e24+2*e01*e14*e22-2*e01*e15*e21+2*e02*e10*e23+2*e02*e11*e24+2*e02*e12*e25+2*e02*e13*e20+2*e02*e14*e21+2*e02*e15*e22+2*e03*e10*e22+2*e03*e12*e20+2*e03*e13*e25+2*e03*e15*e23+2*e03*e16*e28+2*e03*e18*e26+2*e04*e11*e22+2*e04*e12*e21+2*e04*e14*e25+2*e04*e15*e24+2*e04*e17*e28+2*e04*e18*e27-2*e05*e10*e20-2*e05*e11*e21+2*e05*e12*e22+2*e05*e13*e23+2*e05*e14*e24+6*e05*e15*e25-2*e05*e16*e26-2*e05*e17*e27+2*e05*e18*e28+2*e06*e13*e28-2*e06*e15*e26-2*e06*e16*e25+2*e06*e18*e23+2*e07*e14*e28-2*e07*e15*e27-2*e07*e17*e25+2*e07*e18*e24+2*e08*e13*e26+2*e08*e14*e27+2*e08*e15*e28+2*e08*e16*e23+2*e08*e17*e24+2*e08*e18*e25; A(8,9)=-2*e00*e10*e35+2*e00*e12*e33+2*e00*e13*e32-2*e00*e15*e30-2*e01*e11*e35+2*e01*e12*e34+2*e01*e14*e32-2*e01*e15*e31+2*e02*e10*e33+2*e02*e11*e34+2*e02*e12*e35+2*e02*e13*e30+2*e02*e14*e31+2*e02*e15*e32+2*e03*e10*e32+2*e03*e12*e30+2*e03*e13*e35+2*e03*e15*e33+2*e03*e16*e38+2*e03*e18*e36+2*e04*e11*e32+2*e04*e12*e31+2*e04*e14*e35+2*e04*e15*e34+2*e04*e17*e38+2*e04*e18*e37-2*e05*e10*e30-2*e05*e11*e31+2*e05*e12*e32+2*e05*e13*e33+2*e05*e14*e34+6*e05*e15*e35-2*e05*e16*e36-2*e05*e17*e37+2*e05*e18*e38+2*e06*e13*e38-2*e06*e15*e36-2*e06*e16*e35+2*e06*e18*e33+2*e07*e14*e38-2*e07*e15*e37-2*e07*e17*e35+2*e07*e18*e34+2*e08*e13*e36+2*e08*e14*e37+2*e08*e15*e38+2*e08*e16*e33+2*e08*e17*e34+2*e08*e18*e35; A(8,10)=-2*e00*e20*e25+2*e00*e22*e23-2*e01*e21*e25+2*e01*e22*e24+2*e02*e20*e23+2*e02*e21*e24+2*e02*e22*e25+2*e03*e20*e22+2*e03*e23*e25+2*e03*e26*e28+2*e04*e21*e22+2*e04*e24*e25+2*e04*e27*e28-e05*e202-e05*e212+e05*e222+e05*e232+e05*e242+3*e05*e252-e05*e262-e05*e272+e05*e282+2*e06*e23*e28-2*e06*e25*e26+2*e07*e24*e28-2*e07*e25*e27+2*e08*e23*e26+2*e08*e24*e27+2*e08*e25*e28; A(8,11)=-2*e00*e20*e35+2*e00*e22*e33+2*e00*e23*e32-2*e00*e25*e30-2*e01*e21*e35+2*e01*e22*e34+2*e01*e24*e32-2*e01*e25*e31+2*e02*e20*e33+2*e02*e21*e34+2*e02*e22*e35+2*e02*e23*e30+2*e02*e24*e31+2*e02*e25*e32+2*e03*e20*e32+2*e03*e22*e30+2*e03*e23*e35+2*e03*e25*e33+2*e03*e26*e38+2*e03*e28*e36+2*e04*e21*e32+2*e04*e22*e31+2*e04*e24*e35+2*e04*e25*e34+2*e04*e27*e38+2*e04*e28*e37-2*e05*e20*e30-2*e05*e21*e31+2*e05*e22*e32+2*e05*e23*e33+2*e05*e24*e34+6*e05*e25*e35-2*e05*e26*e36-2*e05*e27*e37+2*e05*e28*e38+2*e06*e23*e38-2*e06*e25*e36-2*e06*e26*e35+2*e06*e28*e33+2*e07*e24*e38-2*e07*e25*e37-2*e07*e27*e35+2*e07*e28*e34+2*e08*e23*e36+2*e08*e24*e37+2*e08*e25*e38+2*e08*e26*e33+2*e08*e27*e34+2*e08*e28*e35; A(8,12)=-2*e00*e30*e35+2*e00*e32*e33-2*e01*e31*e35+2*e01*e32*e34+2*e02*e30*e33+2*e02*e31*e34+2*e02*e32*e35+2*e03*e30*e32+2*e03*e33*e35+2*e03*e36*e38+2*e04*e31*e32+2*e04*e34*e35+2*e04*e37*e38-e05*e302-e05*e312+e05*e322+e05*e332+e05*e342+3*e05*e352-e05*e362-e05*e372+e05*e382+2*e06*e33*e38-2*e06*e35*e36+2*e07*e34*e38-2*e07*e35*e37+2*e08*e33*e36+2*e08*e34*e37+2*e08*e35*e38; A(8,13)=-2*e10*e20*e25+2*e10*e22*e23-2*e11*e21*e25+2*e11*e22*e24+2*e12*e20*e23+2*e12*e21*e24+2*e12*e22*e25+2*e13*e20*e22+2*e13*e23*e25+2*e13*e26*e28+2*e14*e21*e22+2*e14*e24*e25+2*e14*e27*e28-e15*e202-e15*e212+e15*e222+e15*e232+e15*e242+3*e15*e252-e15*e262-e15*e272+e15*e282+2*e16*e23*e28-2*e16*e25*e26+2*e17*e24*e28-2*e17*e25*e27+2*e18*e23*e26+2*e18*e24*e27+2*e18*e25*e28; A(8,14)=-2*e10*e20*e35+2*e10*e22*e33+2*e10*e23*e32-2*e10*e25*e30-2*e11*e21*e35+2*e11*e22*e34+2*e11*e24*e32-2*e11*e25*e31+2*e12*e20*e33+2*e12*e21*e34+2*e12*e22*e35+2*e12*e23*e30+2*e12*e24*e31+2*e12*e25*e32+2*e13*e20*e32+2*e13*e22*e30+2*e13*e23*e35+2*e13*e25*e33+2*e13*e26*e38+2*e13*e28*e36+2*e14*e21*e32+2*e14*e22*e31+2*e14*e24*e35+2*e14*e25*e34+2*e14*e27*e38+2*e14*e28*e37-2*e15*e20*e30-2*e15*e21*e31+2*e15*e22*e32+2*e15*e23*e33+2*e15*e24*e34+6*e15*e25*e35-2*e15*e26*e36-2*e15*e27*e37+2*e15*e28*e38+2*e16*e23*e38-2*e16*e25*e36-2*e16*e26*e35+2*e16*e28*e33+2*e17*e24*e38-2*e17*e25*e37-2*e17*e27*e35+2*e17*e28*e34+2*e18*e23*e36+2*e18*e24*e37+2*e18*e25*e38+2*e18*e26*e33+2*e18*e27*e34+2*e18*e28*e35; A(8,15)=-2*e10*e30*e35+2*e10*e32*e33-2*e11*e31*e35+2*e11*e32*e34+2*e12*e30*e33+2*e12*e31*e34+2*e12*e32*e35+2*e13*e30*e32+2*e13*e33*e35+2*e13*e36*e38+2*e14*e31*e32+2*e14*e34*e35+2*e14*e37*e38-e15*e302-e15*e312+e15*e322+e15*e332+e15*e342+3*e15*e352-e15*e362-e15*e372+e15*e382+2*e16*e33*e38-2*e16*e35*e36+2*e17*e34*e38-2*e17*e35*e37+2*e18*e33*e36+2*e18*e34*e37+2*e18*e35*e38; A(8,16)=-e202*e25+2*e20*e22*e23-e212*e25+2*e21*e22*e24+e222*e25+e232*e25+2*e23*e26*e28+e242*e25+2*e24*e27*e28+e253-e25*e262-e25*e272+e25*e282; A(8,17)=-e202*e35+2*e20*e22*e33+2*e20*e23*e32-2*e20*e25*e30-e212*e35+2*e21*e22*e34+2*e21*e24*e32-2*e21*e25*e31+e222*e35+2*e22*e23*e30+2*e22*e24*e31+2*e22*e25*e32+e232*e35+2*e23*e25*e33+2*e23*e26*e38+2*e23*e28*e36+e242*e35+2*e24*e25*e34+2*e24*e27*e38+2*e24*e28*e37+3*e252*e35-2*e25*e26*e36-2*e25*e27*e37+2*e25*e28*e38-e262*e35+2*e26*e28*e33-e272*e35+2*e27*e28*e34+e282*e35; A(8,18)=-2*e20*e30*e35+2*e20*e32*e33-2*e21*e31*e35+2*e21*e32*e34+2*e22*e30*e33+2*e22*e31*e34+2*e22*e32*e35+2*e23*e30*e32+2*e23*e33*e35+2*e23*e36*e38+2*e24*e31*e32+2*e24*e34*e35+2*e24*e37*e38-e25*e302-e25*e312+e25*e322+e25*e332+e25*e342+3*e25*e352-e25*e362-e25*e372+e25*e382+2*e26*e33*e38-2*e26*e35*e36+2*e27*e34*e38-2*e27*e35*e37+2*e28*e33*e36+2*e28*e34*e37+2*e28*e35*e38; A(8,19)=-e302*e35+2*e30*e32*e33-e312*e35+2*e31*e32*e34+e322*e35+e332*e35+2*e33*e36*e38+e342*e35+2*e34*e37*e38+e353-e35*e362-e35*e372+e35*e382; A(9,0)=-e002*e08+2*e00*e02*e06-e012*e08+2*e01*e02*e07+e022*e08-e032*e08+2*e03*e05*e06-e042*e08+2*e04*e05*e07+e052*e08+e062*e08+e072*e08+e083; A(9,1)=-e102*e18+2*e10*e12*e16-e112*e18+2*e11*e12*e17+e122*e18-e132*e18+2*e13*e15*e16-e142*e18+2*e14*e15*e17+e152*e18+e162*e18+e172*e18+e183; A(9,2)=-e002*e18+2*e00*e02*e16+2*e00*e06*e12-2*e00*e08*e10-e012*e18+2*e01*e02*e17+2*e01*e07*e12-2*e01*e08*e11+e022*e18+2*e02*e06*e10+2*e02*e07*e11+2*e02*e08*e12-e032*e18+2*e03*e05*e16+2*e03*e06*e15-2*e03*e08*e13-e042*e18+2*e04*e05*e17+2*e04*e07*e15-2*e04*e08*e14+e052*e18+2*e05*e06*e13+2*e05*e07*e14+2*e05*e08*e15+e062*e18+2*e06*e08*e16+e072*e18+2*e07*e08*e17+3*e082*e18; A(9,3)=-2*e00*e10*e18+2*e00*e12*e16-2*e01*e11*e18+2*e01*e12*e17+2*e02*e10*e16+2*e02*e11*e17+2*e02*e12*e18-2*e03*e13*e18+2*e03*e15*e16-2*e04*e14*e18+2*e04*e15*e17+2*e05*e13*e16+2*e05*e14*e17+2*e05*e15*e18+2*e06*e10*e12+2*e06*e13*e15+2*e06*e16*e18+2*e07*e11*e12+2*e07*e14*e15+2*e07*e17*e18-e08*e102-e08*e112+e08*e122-e08*e132-e08*e142+e08*e152+e08*e162+e08*e172+3*e08*e182; A(9,4)=-e002*e28+2*e00*e02*e26+2*e00*e06*e22-2*e00*e08*e20-e012*e28+2*e01*e02*e27+2*e01*e07*e22-2*e01*e08*e21+e022*e28+2*e02*e06*e20+2*e02*e07*e21+2*e02*e08*e22-e032*e28+2*e03*e05*e26+2*e03*e06*e25-2*e03*e08*e23-e042*e28+2*e04*e05*e27+2*e04*e07*e25-2*e04*e08*e24+e052*e28+2*e05*e06*e23+2*e05*e07*e24+2*e05*e08*e25+e062*e28+2*e06*e08*e26+e072*e28+2*e07*e08*e27+3*e082*e28; A(9,5)=-e002*e38+2*e00*e02*e36+2*e00*e06*e32-2*e00*e08*e30-e012*e38+2*e01*e02*e37+2*e01*e07*e32-2*e01*e08*e31+e022*e38+2*e02*e06*e30+2*e02*e07*e31+2*e02*e08*e32-e032*e38+2*e03*e05*e36+2*e03*e06*e35-2*e03*e08*e33-e042*e38+2*e04*e05*e37+2*e04*e07*e35-2*e04*e08*e34+e052*e38+2*e05*e06*e33+2*e05*e07*e34+2*e05*e08*e35+e062*e38+2*e06*e08*e36+e072*e38+2*e07*e08*e37+3*e082*e38; A(9,6)=-e102*e28+2*e10*e12*e26+2*e10*e16*e22-2*e10*e18*e20-e112*e28+2*e11*e12*e27+2*e11*e17*e22-2*e11*e18*e21+e122*e28+2*e12*e16*e20+2*e12*e17*e21+2*e12*e18*e22-e132*e28+2*e13*e15*e26+2*e13*e16*e25-2*e13*e18*e23-e142*e28+2*e14*e15*e27+2*e14*e17*e25-2*e14*e18*e24+e152*e28+2*e15*e16*e23+2*e15*e17*e24+2*e15*e18*e25+e162*e28+2*e16*e18*e26+e172*e28+2*e17*e18*e27+3*e182*e28; A(9,7)=-e102*e38+2*e10*e12*e36+2*e10*e16*e32-2*e10*e18*e30-e112*e38+2*e11*e12*e37+2*e11*e17*e32-2*e11*e18*e31+e122*e38+2*e12*e16*e30+2*e12*e17*e31+2*e12*e18*e32-e132*e38+2*e13*e15*e36+2*e13*e16*e35-2*e13*e18*e33-e142*e38+2*e14*e15*e37+2*e14*e17*e35-2*e14*e18*e34+e152*e38+2*e15*e16*e33+2*e15*e17*e34+2*e15*e18*e35+e162*e38+2*e16*e18*e36+e172*e38+2*e17*e18*e37+3*e182*e38; A(9,8)=-2*e00*e10*e28+2*e00*e12*e26+2*e00*e16*e22-2*e00*e18*e20-2*e01*e11*e28+2*e01*e12*e27+2*e01*e17*e22-2*e01*e18*e21+2*e02*e10*e26+2*e02*e11*e27+2*e02*e12*e28+2*e02*e16*e20+2*e02*e17*e21+2*e02*e18*e22-2*e03*e13*e28+2*e03*e15*e26+2*e03*e16*e25-2*e03*e18*e23-2*e04*e14*e28+2*e04*e15*e27+2*e04*e17*e25-2*e04*e18*e24+2*e05*e13*e26+2*e05*e14*e27+2*e05*e15*e28+2*e05*e16*e23+2*e05*e17*e24+2*e05*e18*e25+2*e06*e10*e22+2*e06*e12*e20+2*e06*e13*e25+2*e06*e15*e23+2*e06*e16*e28+2*e06*e18*e26+2*e07*e11*e22+2*e07*e12*e21+2*e07*e14*e25+2*e07*e15*e24+2*e07*e17*e28+2*e07*e18*e27-2*e08*e10*e20-2*e08*e11*e21+2*e08*e12*e22-2*e08*e13*e23-2*e08*e14*e24+2*e08*e15*e25+2*e08*e16*e26+2*e08*e17*e27+6*e08*e18*e28; A(9,9)=-2*e00*e10*e38+2*e00*e12*e36+2*e00*e16*e32-2*e00*e18*e30-2*e01*e11*e38+2*e01*e12*e37+2*e01*e17*e32-2*e01*e18*e31+2*e02*e10*e36+2*e02*e11*e37+2*e02*e12*e38+2*e02*e16*e30+2*e02*e17*e31+2*e02*e18*e32-2*e03*e13*e38+2*e03*e15*e36+2*e03*e16*e35-2*e03*e18*e33-2*e04*e14*e38+2*e04*e15*e37+2*e04*e17*e35-2*e04*e18*e34+2*e05*e13*e36+2*e05*e14*e37+2*e05*e15*e38+2*e05*e16*e33+2*e05*e17*e34+2*e05*e18*e35+2*e06*e10*e32+2*e06*e12*e30+2*e06*e13*e35+2*e06*e15*e33+2*e06*e16*e38+2*e06*e18*e36+2*e07*e11*e32+2*e07*e12*e31+2*e07*e14*e35+2*e07*e15*e34+2*e07*e17*e38+2*e07*e18*e37-2*e08*e10*e30-2*e08*e11*e31+2*e08*e12*e32-2*e08*e13*e33-2*e08*e14*e34+2*e08*e15*e35+2*e08*e16*e36+2*e08*e17*e37+6*e08*e18*e38; A(9,10)=-2*e00*e20*e28+2*e00*e22*e26-2*e01*e21*e28+2*e01*e22*e27+2*e02*e20*e26+2*e02*e21*e27+2*e02*e22*e28-2*e03*e23*e28+2*e03*e25*e26-2*e04*e24*e28+2*e04*e25*e27+2*e05*e23*e26+2*e05*e24*e27+2*e05*e25*e28+2*e06*e20*e22+2*e06*e23*e25+2*e06*e26*e28+2*e07*e21*e22+2*e07*e24*e25+2*e07*e27*e28-e08*e202-e08*e212+e08*e222-e08*e232-e08*e242+e08*e252+e08*e262+e08*e272+3*e08*e282; A(9,11)=-2*e00*e20*e38+2*e00*e22*e36+2*e00*e26*e32-2*e00*e28*e30-2*e01*e21*e38+2*e01*e22*e37+2*e01*e27*e32-2*e01*e28*e31+2*e02*e20*e36+2*e02*e21*e37+2*e02*e22*e38+2*e02*e26*e30+2*e02*e27*e31+2*e02*e28*e32-2*e03*e23*e38+2*e03*e25*e36+2*e03*e26*e35-2*e03*e28*e33-2*e04*e24*e38+2*e04*e25*e37+2*e04*e27*e35-2*e04*e28*e34+2*e05*e23*e36+2*e05*e24*e37+2*e05*e25*e38+2*e05*e26*e33+2*e05*e27*e34+2*e05*e28*e35+2*e06*e20*e32+2*e06*e22*e30+2*e06*e23*e35+2*e06*e25*e33+2*e06*e26*e38+2*e06*e28*e36+2*e07*e21*e32+2*e07*e22*e31+2*e07*e24*e35+2*e07*e25*e34+2*e07*e27*e38+2*e07*e28*e37-2*e08*e20*e30-2*e08*e21*e31+2*e08*e22*e32-2*e08*e23*e33-2*e08*e24*e34+2*e08*e25*e35+2*e08*e26*e36+2*e08*e27*e37+6*e08*e28*e38; A(9,12)=-2*e00*e30*e38+2*e00*e32*e36-2*e01*e31*e38+2*e01*e32*e37+2*e02*e30*e36+2*e02*e31*e37+2*e02*e32*e38-2*e03*e33*e38+2*e03*e35*e36-2*e04*e34*e38+2*e04*e35*e37+2*e05*e33*e36+2*e05*e34*e37+2*e05*e35*e38+2*e06*e30*e32+2*e06*e33*e35+2*e06*e36*e38+2*e07*e31*e32+2*e07*e34*e35+2*e07*e37*e38-e08*e302-e08*e312+e08*e322-e08*e332-e08*e342+e08*e352+e08*e362+e08*e372+3*e08*e382; A(9,13)=-2*e10*e20*e28+2*e10*e22*e26-2*e11*e21*e28+2*e11*e22*e27+2*e12*e20*e26+2*e12*e21*e27+2*e12*e22*e28-2*e13*e23*e28+2*e13*e25*e26-2*e14*e24*e28+2*e14*e25*e27+2*e15*e23*e26+2*e15*e24*e27+2*e15*e25*e28+2*e16*e20*e22+2*e16*e23*e25+2*e16*e26*e28+2*e17*e21*e22+2*e17*e24*e25+2*e17*e27*e28-e18*e202-e18*e212+e18*e222-e18*e232-e18*e242+e18*e252+e18*e262+e18*e272+3*e18*e282; A(9,14)=-2*e10*e20*e38+2*e10*e22*e36+2*e10*e26*e32-2*e10*e28*e30-2*e11*e21*e38+2*e11*e22*e37+2*e11*e27*e32-2*e11*e28*e31+2*e12*e20*e36+2*e12*e21*e37+2*e12*e22*e38+2*e12*e26*e30+2*e12*e27*e31+2*e12*e28*e32-2*e13*e23*e38+2*e13*e25*e36+2*e13*e26*e35-2*e13*e28*e33-2*e14*e24*e38+2*e14*e25*e37+2*e14*e27*e35-2*e14*e28*e34+2*e15*e23*e36+2*e15*e24*e37+2*e15*e25*e38+2*e15*e26*e33+2*e15*e27*e34+2*e15*e28*e35+2*e16*e20*e32+2*e16*e22*e30+2*e16*e23*e35+2*e16*e25*e33+2*e16*e26*e38+2*e16*e28*e36+2*e17*e21*e32+2*e17*e22*e31+2*e17*e24*e35+2*e17*e25*e34+2*e17*e27*e38+2*e17*e28*e37-2*e18*e20*e30-2*e18*e21*e31+2*e18*e22*e32-2*e18*e23*e33-2*e18*e24*e34+2*e18*e25*e35+2*e18*e26*e36+2*e18*e27*e37+6*e18*e28*e38; A(9,15)=-2*e10*e30*e38+2*e10*e32*e36-2*e11*e31*e38+2*e11*e32*e37+2*e12*e30*e36+2*e12*e31*e37+2*e12*e32*e38-2*e13*e33*e38+2*e13*e35*e36-2*e14*e34*e38+2*e14*e35*e37+2*e15*e33*e36+2*e15*e34*e37+2*e15*e35*e38+2*e16*e30*e32+2*e16*e33*e35+2*e16*e36*e38+2*e17*e31*e32+2*e17*e34*e35+2*e17*e37*e38-e18*e302-e18*e312+e18*e322-e18*e332-e18*e342+e18*e352+e18*e362+e18*e372+3*e18*e382; A(9,16)=-e202*e28+2*e20*e22*e26-e212*e28+2*e21*e22*e27+e222*e28-e232*e28+2*e23*e25*e26-e242*e28+2*e24*e25*e27+e252*e28+e262*e28+e272*e28+e283; A(9,17)=-e202*e38+2*e20*e22*e36+2*e20*e26*e32-2*e20*e28*e30-e212*e38+2*e21*e22*e37+2*e21*e27*e32-2*e21*e28*e31+e222*e38+2*e22*e26*e30+2*e22*e27*e31+2*e22*e28*e32-e232*e38+2*e23*e25*e36+2*e23*e26*e35-2*e23*e28*e33-e242*e38+2*e24*e25*e37+2*e24*e27*e35-2*e24*e28*e34+e252*e38+2*e25*e26*e33+2*e25*e27*e34+2*e25*e28*e35+e262*e38+2*e26*e28*e36+e272*e38+2*e27*e28*e37+3*e282*e38; A(9,18)=-2*e20*e30*e38+2*e20*e32*e36-2*e21*e31*e38+2*e21*e32*e37+2*e22*e30*e36+2*e22*e31*e37+2*e22*e32*e38-2*e23*e33*e38+2*e23*e35*e36-2*e24*e34*e38+2*e24*e35*e37+2*e25*e33*e36+2*e25*e34*e37+2*e25*e35*e38+2*e26*e30*e32+2*e26*e33*e35+2*e26*e36*e38+2*e27*e31*e32+2*e27*e34*e35+2*e27*e37*e38-e28*e302-e28*e312+e28*e322-e28*e332-e28*e342+e28*e352+e28*e362+e28*e372+3*e28*e382; A(9,19)=-e302*e38+2*e30*e32*e36-e312*e38+2*e31*e32*e37+e322*e38-e332*e38+2*e33*e35*e36-e342*e38+2*e34*e35*e37+e352*e38+e362*e38+e372*e38+e383; } double opengv::relative_pose::modules::fivept_nister::polyVal( const Eigen::MatrixXd & p, double x) { size_t degree = p.cols(); double value = 0.0; for( size_t power = degree; power > 0; power--) value += p(0, (int)(degree-power))*pow(x,(int)(power-1)); return value; } void opengv::relative_pose::modules::fivept_nister:: computeSeventhOrderPolynomial( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ) { p_out = Eigen::Matrix::Zero(); p_out[0] = p1[0]*p2[0]; p_out[1] = p1[0]*p2[1] + p1[1]*p2[0]; p_out[2] = p1[0]*p2[2] + p1[1]*p2[1] + p1[2]*p2[0]; p_out[3] = p1[0]*p2[3] + p1[1]*p2[2] + p1[2]*p2[1] + p1[3]*p2[0]; p_out[4] = p1[1]*p2[3] + p1[2]*p2[2] + p1[3]*p2[1] + p1[4]*p2[0]; p_out[5] = p1[2]*p2[3] + p1[3]*p2[2] + p1[4]*p2[1]; p_out[6] = p1[3]*p2[3] + p1[4]*p2[2]; p_out[7] = p1[4]*p2[3]; } void opengv::relative_pose::modules::fivept_nister:: computeSixthOrderPolynomial( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ) { p_out = Eigen::Matrix::Zero(); p_out[0] = p1[0]*p2[0]; p_out[1] = p1[0]*p2[1] + p1[1]*p2[0]; p_out[2] = p1[0]*p2[2] + p1[1]*p2[1] + p1[2]*p2[0]; p_out[3] = p1[0]*p2[3] + p1[1]*p2[2] + p1[2]*p2[1] + p1[3]*p2[0]; p_out[4] = p1[1]*p2[3] + p1[2]*p2[2] + p1[3]*p2[1]; p_out[5] = p1[2]*p2[3] + p1[3]*p2[2]; p_out[6] = p1[3]*p2[3]; } void opengv::relative_pose::modules::fivept_nister:: computeTenthOrderPolynomialFrom73( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ) { p_out = Eigen::Matrix::Zero(); p_out[0] = p1[0]*p2[0]; p_out[1] = p1[0]*p2[1] + p1[1]*p2[0]; p_out[2] = p1[0]*p2[2] + p1[1]*p2[1] + p1[2]*p2[0]; p_out[3] = p1[0]*p2[3] + p1[1]*p2[2] + p1[2]*p2[1] + p1[3]*p2[0]; p_out[4] = p1[1]*p2[3] + p1[2]*p2[2] + p1[3]*p2[1] + p1[4]*p2[0]; p_out[5] = p1[2]*p2[3] + p1[3]*p2[2] + p1[4]*p2[1] + p1[5]*p2[0]; p_out[6] = p1[3]*p2[3] + p1[4]*p2[2] + p1[5]*p2[1] + p1[6]*p2[0]; p_out[7] = p1[4]*p2[3] + p1[5]*p2[2] + p1[6]*p2[1] + p1[7]*p2[0]; p_out[8] = p1[5]*p2[3] + p1[6]*p2[2] + p1[7]*p2[1]; p_out[9] = p1[6]*p2[3] + p1[7]*p2[2]; p_out[10] = p1[7]*p2[3]; } void opengv::relative_pose::modules::fivept_nister:: computeTenthOrderPolynomialFrom64( const Eigen::Matrix & p1, const Eigen::Matrix & p2, Eigen::Matrix & p_out ) { p_out = Eigen::Matrix::Zero(); p_out[0] = p1[0]*p2[0]; p_out[1] = p1[0]*p2[1] + p1[1]*p2[0]; p_out[2] = p1[0]*p2[2] + p1[1]*p2[1] + p1[2]*p2[0]; p_out[3] = p1[0]*p2[3] + p1[1]*p2[2] + p1[2]*p2[1] + p1[3]*p2[0]; p_out[4] = p1[0]*p2[4] + p1[1]*p2[3] + p1[2]*p2[2] + p1[3]*p2[1] + p1[4]*p2[0]; p_out[5] = p1[1]*p2[4] + p1[2]*p2[3] + p1[3]*p2[2] + p1[4]*p2[1] + p1[5]*p2[0]; p_out[6] = p1[2]*p2[4] + p1[3]*p2[3] + p1[4]*p2[2] + p1[5]*p2[1] + p1[6]*p2[0]; p_out[7] = p1[3]*p2[4] + p1[4]*p2[3] + p1[5]*p2[2] + p1[6]*p2[1]; p_out[8] = p1[4]*p2[4] + p1[5]*p2[3] + p1[6]*p2[2]; p_out[9] = p1[5]*p2[4] + p1[6]*p2[3]; p_out[10] = p1[6]*p2[4]; } namespace opengv { namespace relative_pose { namespace modules { namespace fivept_nister { struct PollishCoefficientsFunctor : OptimizationFunctor { const Eigen::Matrix & _A; PollishCoefficientsFunctor( const Eigen::Matrix & A ) : OptimizationFunctor(3,10), _A(A) {} int operator()(const VectorXd &x, VectorXd &fvec) const { assert( x.size() == 3 ); assert( (unsigned int) fvec.size() == 10); //create the monomials vector Eigen::Matrix monomials; monomials[0] = pow(x[0],3); monomials[1] = pow(x[1],3); monomials[2] = pow(x[0],2)*x[1]; monomials[3] = x[0]*pow(x[1],2); monomials[4] = pow(x[0],2)*x[2]; monomials[5] = pow(x[0],2); monomials[6] = pow(x[1],2)*x[2]; monomials[7] = pow(x[1],2); monomials[8] = x[0]*x[1]*x[2]; monomials[9] = x[0]*x[1]; monomials[10] = x[0]*pow(x[2],2); monomials[11] = x[0]*x[2]; monomials[12] = x[0]; monomials[13] = x[1]*pow(x[2],2); monomials[14] = x[1]*x[2]; monomials[15] = x[1]; monomials[16] = pow(x[2],3); monomials[17] = pow(x[2],2); monomials[18] = x[2]; monomials[19] = 1.0; fvec = _A*monomials; return 0; } }; } } } } void opengv::relative_pose::modules::fivept_nister::pollishCoefficients( const Eigen::Matrix & A, double & x_coeff, double & y_coeff, double & z_coeff) { const int n=3; VectorXd x(n); x[0] = x_coeff; x[1] = y_coeff; x[2] = z_coeff; PollishCoefficientsFunctor functor( A ); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 1.E10*NumTraits::epsilon(); lm.parameters.xtol = 1.E10*NumTraits::epsilon(); lm.parameters.maxfev = 5; lm.minimize(x); x_coeff = x[0]; y_coeff = x[1]; z_coeff = x[2]; } opengv/src/relative_pose/modules/eigensolver/0000775016516101651610000000000013344612246020431 5ustar dimadimaopengv/src/relative_pose/modules/eigensolver/modules.cpp0000664016516101651610000005053613344612246022616 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include double opengv::relative_pose::modules::eigensolver::getSmallestEV( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley, Eigen::Matrix3d & M ) { M = composeM(xxF,yyF,zzF,xyF,yzF,zxF,cayley); //Retrieve the smallest Eigenvalue by the following closed form solution double b = -M(0,0)-M(1,1)-M(2,2); double c = -pow(M(0,2),2)-pow(M(1,2),2)-pow(M(0,1),2)+ M(0,0)*M(1,1)+M(0,0)*M(2,2)+M(1,1)*M(2,2); double d = M(1,1)*pow(M(0,2),2)+M(0,0)*pow(M(1,2),2)+M(2,2)*pow(M(0,1),2)- M(0,0)*M(1,1)*M(2,2)-2*M(0,1)*M(1,2)*M(0,2); double s = 2*pow(b,3)-9*b*c+27*d; double t = 4*pow((pow(b,2)-3*c),3); double alpha = acos(s/sqrt(t)); double beta = alpha/3; double y = cos(beta); double r = 0.5*sqrt(t); double w = pow(r,(1.0/3.0)); double k = w*y; double smallestEV = (-b-2*k)/3; return smallestEV; } double opengv::relative_pose::modules::eigensolver:: getSmallestEVwithJacobian( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley, Eigen::Matrix & jacobian) { Eigen::Matrix3d M_jac1 = Eigen::Matrix3d::Zero(); Eigen::Matrix3d M_jac2 = Eigen::Matrix3d::Zero(); Eigen::Matrix3d M_jac3 = Eigen::Matrix3d::Zero(); Eigen::Matrix3d M = composeMwithJacobians( xxF,yyF,zzF,xyF,yzF,zxF,cayley,M_jac1,M_jac2,M_jac3); //Retrieve the smallest Eigenvalue by the following closed form solution. //Plus Jacobian. double b = -M(0,0)-M(1,1)-M(2,2); double b_jac1 = -M_jac1(0,0)-M_jac1(1,1)-M_jac1(2,2); double b_jac2 = -M_jac2(0,0)-M_jac2(1,1)-M_jac2(2,2); double b_jac3 = -M_jac3(0,0)-M_jac3(1,1)-M_jac3(2,2); double c = -pow(M(0,2),2)-pow(M(1,2),2)-pow(M(0,1),2)+ M(0,0)*M(1,1)+M(0,0)*M(2,2)+M(1,1)*M(2,2); double c_jac1 = -2.0*M(0,2)*M_jac1(0,2)-2.0*M(1,2)*M_jac1(1,2)-2.0*M(0,1)*M_jac1(0,1) +M_jac1(0,0)*M(1,1)+M(0,0)*M_jac1(1,1)+M_jac1(0,0)*M(2,2) +M(0,0)*M_jac1(2,2)+M_jac1(1,1)*M(2,2)+M(1,1)*M_jac1(2,2); double c_jac2 = -2.0*M(0,2)*M_jac2(0,2)-2.0*M(1,2)*M_jac2(1,2)-2.0*M(0,1)*M_jac2(0,1) +M_jac2(0,0)*M(1,1)+M(0,0)*M_jac2(1,1)+M_jac2(0,0)*M(2,2) +M(0,0)*M_jac2(2,2)+M_jac2(1,1)*M(2,2)+M(1,1)*M_jac2(2,2); double c_jac3 = -2.0*M(0,2)*M_jac3(0,2)-2.0*M(1,2)*M_jac3(1,2)-2.0*M(0,1)*M_jac3(0,1) +M_jac3(0,0)*M(1,1)+M(0,0)*M_jac3(1,1)+M_jac3(0,0)*M(2,2) +M(0,0)*M_jac3(2,2)+M_jac3(1,1)*M(2,2)+M(1,1)*M_jac3(2,2); double d = M(1,1)*pow(M(0,2),2)+M(0,0)*pow(M(1,2),2)+M(2,2)*pow(M(0,1),2)- M(0,0)*M(1,1)*M(2,2)-2*M(0,1)*M(1,2)*M(0,2); double d_jac1 = M_jac1(1,1)*pow(M(0,2),2)+M(1,1)*2*M(0,2)*M_jac1(0,2) +M_jac1(0,0)*pow(M(1,2),2)+M(0,0)*2.0*M(1,2)*M_jac1(1,2) +M_jac1(2,2)*pow(M(0,1),2)+M(2,2)*2.0*M(0,1)*M_jac1(0,1) -M_jac1(0,0)*M(1,1)*M(2,2)-M(0,0)*M_jac1(1,1)*M(2,2) -M(0,0)*M(1,1)*M_jac1(2,2)-2.0*(M_jac1(0,1)*M(1,2)*M(0,2) +M(0,1)*M_jac1(1,2)*M(0,2)+M(0,1)*M(1,2)*M_jac1(0,2)); double d_jac2 = M_jac2(1,1)*pow(M(0,2),2)+M(1,1)*2*M(0,2)*M_jac2(0,2) +M_jac2(0,0)*pow(M(1,2),2)+M(0,0)*2.0*M(1,2)*M_jac2(1,2) +M_jac2(2,2)*pow(M(0,1),2)+M(2,2)*2.0*M(0,1)*M_jac2(0,1) -M_jac2(0,0)*M(1,1)*M(2,2)-M(0,0)*M_jac2(1,1)*M(2,2) -M(0,0)*M(1,1)*M_jac2(2,2)-2.0*(M_jac2(0,1)*M(1,2)*M(0,2) +M(0,1)*M_jac2(1,2)*M(0,2)+M(0,1)*M(1,2)*M_jac2(0,2)); double d_jac3 = M_jac3(1,1)*pow(M(0,2),2)+M(1,1)*2*M(0,2)*M_jac3(0,2) +M_jac3(0,0)*pow(M(1,2),2)+M(0,0)*2.0*M(1,2)*M_jac3(1,2) +M_jac3(2,2)*pow(M(0,1),2)+M(2,2)*2.0*M(0,1)*M_jac3(0,1) -M_jac3(0,0)*M(1,1)*M(2,2)-M(0,0)*M_jac3(1,1)*M(2,2) -M(0,0)*M(1,1)*M_jac3(2,2)-2.0*(M_jac3(0,1)*M(1,2)*M(0,2) +M(0,1)*M_jac3(1,2)*M(0,2)+M(0,1)*M(1,2)*M_jac3(0,2)); double s = 2*pow(b,3)-9*b*c+27*d; double t = 4*pow((pow(b,2)-3*c),3); double s_jac1 = 2.0*3.0*pow(b,2)*b_jac1-9.0*b_jac1*c-9.0*b*c_jac1+27.0*d_jac1; double s_jac2 = 2.0*3.0*pow(b,2)*b_jac2-9.0*b_jac2*c-9.0*b*c_jac2+27.0*d_jac2; double s_jac3 = 2.0*3.0*pow(b,2)*b_jac3-9.0*b_jac3*c-9.0*b*c_jac3+27.0*d_jac3; double t_jac1 = 4.0*3.0*pow((pow(b,2)-3.0*c),2)*(2.0*b*b_jac1-3.0*c_jac1); double t_jac2 = 4.0*3.0*pow((pow(b,2)-3.0*c),2)*(2.0*b*b_jac2-3.0*c_jac2); double t_jac3 = 4.0*3.0*pow((pow(b,2)-3.0*c),2)*(2.0*b*b_jac3-3.0*c_jac3); double alpha = acos(s/sqrt(t)); double alpha_jac1 = -1.0/sqrt(1.0-(pow(s,2)/t)) * (s_jac1*sqrt(t)-s*0.5*pow(t,-0.5)*t_jac1)/t; double alpha_jac2 = -1.0/sqrt(1.0-(pow(s,2)/t)) * (s_jac2*sqrt(t)-s*0.5*pow(t,-0.5)*t_jac2)/t; double alpha_jac3 = -1.0/sqrt(1.0-(pow(s,2)/t)) * (s_jac3*sqrt(t)-s*0.5*pow(t,-0.5)*t_jac3)/t; double beta = alpha/3; double beta_jac1 = alpha_jac1/3.0; double beta_jac2 = alpha_jac2/3.0; double beta_jac3 = alpha_jac3/3.0; double y = cos(beta); double y_jac1 = -sin(beta)*beta_jac1; double y_jac2 = -sin(beta)*beta_jac2; double y_jac3 = -sin(beta)*beta_jac3; double r = 0.5*sqrt(t); double r_jac1 = 0.25*pow(t,-0.5)*t_jac1; double r_jac2 = 0.25*pow(t,-0.5)*t_jac2; double r_jac3 = 0.25*pow(t,-0.5)*t_jac3; double w = pow(r,(1.0/3.0)); double w_jac1 = (1.0/3.0)*pow(r,-2.0/3.0)*r_jac1; double w_jac2 = (1.0/3.0)*pow(r,-2.0/3.0)*r_jac2; double w_jac3 = (1.0/3.0)*pow(r,-2.0/3.0)*r_jac3; double k = w*y; double k_jac1 = w_jac1*y+w*y_jac1; double k_jac2 = w_jac2*y+w*y_jac2; double k_jac3 = w_jac3*y+w*y_jac3; double smallestEV = (-b-2*k)/3; double smallestEV_jac1 = (-b_jac1-2.0*k_jac1)/3.0; double smallestEV_jac2 = (-b_jac2-2.0*k_jac2)/3.0; double smallestEV_jac3 = (-b_jac3-2.0*k_jac3)/3.0; jacobian(0,0) = smallestEV_jac1; jacobian(0,1) = smallestEV_jac2; jacobian(0,2) = smallestEV_jac3; return smallestEV; } Eigen::Matrix3d opengv::relative_pose::modules::eigensolver::composeM( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley) { Eigen::Matrix3d M; rotation_t R = math::cayley2rot_reduced(cayley); //Fill the matrix M using the precomputed summation terms double temp; temp = R.row(2)*yyF*R.row(2).transpose(); M(0,0) = temp; temp = -2.0*R.row(2)*yzF*R.row(1).transpose(); M(0,0) += temp; temp = R.row(1)*zzF*R.row(1).transpose(); M(0,0) += temp; temp = R.row(2)*yzF*R.row(0).transpose(); M(0,1) = temp; temp = -1.0*R.row(2)*xyF*R.row(2).transpose(); M(0,1) += temp; temp = -1.0*R.row(1)*zzF*R.row(0).transpose(); M(0,1) += temp; temp = R.row(1)*zxF*R.row(2).transpose(); M(0,1) += temp; temp = R.row(2)*xyF*R.row(1).transpose(); M(0,2) = temp; temp = -1.0*R.row(2)*yyF*R.row(0).transpose(); M(0,2) += temp; temp = -1.0*R.row(1)*zxF*R.row(1).transpose(); M(0,2) += temp; temp = R.row(1)*yzF*R.row(0).transpose(); M(0,2) += temp; temp = R.row(0)*zzF*R.row(0).transpose(); M(1,1) = temp; temp = -2.0*R.row(0)*zxF*R.row(2).transpose(); M(1,1) += temp; temp = R.row(2)*xxF*R.row(2).transpose(); M(1,1) += temp; temp = R.row(0)*zxF*R.row(1).transpose(); M(1,2) = temp; temp = -1.0*R.row(0)*yzF*R.row(0).transpose(); M(1,2) += temp; temp = -1.0*R.row(2)*xxF*R.row(1).transpose(); M(1,2) += temp; temp = R.row(2)*xyF*R.row(0).transpose(); M(1,2) += temp; temp = R.row(1)*xxF*R.row(1).transpose(); M(2,2) = temp; temp = -2.0*R.row(0)*xyF*R.row(1).transpose(); M(2,2) += temp; temp = R.row(0)*yyF*R.row(0).transpose(); M(2,2) += temp; M(1,0) = M(0,1); M(2,0) = M(0,2); M(2,1) = M(1,2); return M; } Eigen::Matrix3d opengv::relative_pose::modules::eigensolver::composeMwithJacobians( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const cayley_t & cayley, Eigen::Matrix3d & M_jac1, Eigen::Matrix3d & M_jac2, Eigen::Matrix3d & M_jac3 ) { rotation_t R = math::cayley2rot_reduced(cayley); rotation_t R_jac1; rotation_t R_jac2; rotation_t R_jac3; R_jac1(0,0) = 2*cayley[0]; R_jac1(0,1) = 2*cayley[1]; R_jac1(0,2) = 2*cayley[2]; R_jac1(1,0) = 2*cayley[1]; R_jac1(1,1) = -2*cayley[0]; R_jac1(1,2) = -2; R_jac1(2,0) = 2*cayley[2]; R_jac1(2,1) = 2; R_jac1(2,2) = -2*cayley[0]; R_jac2(0,0) = -2*cayley[1]; R_jac2(0,1) = 2*cayley[0]; R_jac2(0,2) = 2; R_jac2(1,0) = 2*cayley[0]; R_jac2(1,1) = 2*cayley[1]; R_jac2(1,2) = 2*cayley[2]; R_jac2(2,0) = -2; R_jac2(2,1) = 2*cayley[2]; R_jac2(2,2) = -2*cayley[1]; R_jac3(0,0) = -2*cayley[2]; R_jac3(0,1) = -2; R_jac3(0,2) = 2*cayley[0]; R_jac3(1,0) = 2; R_jac3(1,1) = -2*cayley[2]; R_jac3(1,2) = 2*cayley[1]; R_jac3(2,0) = 2*cayley[0]; R_jac3(2,1) = 2*cayley[1]; R_jac3(2,2) = 2*cayley[2]; //Fill the matrix M using the precomputed summation terms. Plus Jacobian. Eigen::Matrix3d M; double temp; temp = R.row(2)*yyF*R.row(2).transpose(); M(0,0) = temp; temp = -2.0*R.row(2)*yzF*R.row(1).transpose(); M(0,0) += temp; temp = R.row(1)*zzF*R.row(1).transpose(); M(0,0) += temp; temp = 2.0*R_jac1.row(2)*yyF*R.row(2).transpose(); M_jac1(0,0) = temp; temp = -2.0*R_jac1.row(2)*yzF*R.row(1).transpose(); M_jac1(0,0) += temp; temp = -2.0*R.row(2)*yzF*R_jac1.row(1).transpose(); M_jac1(0,0) += temp; temp = 2.0*R_jac1.row(1)*zzF*R.row(1).transpose(); M_jac1(0,0) += temp; temp = 2.0*R_jac2.row(2)*yyF*R.row(2).transpose(); M_jac2(0,0) = temp; temp = -2.0*R_jac2.row(2)*yzF*R.row(1).transpose(); M_jac2(0,0) += temp; temp = -2.0*R.row(2)*yzF*R_jac2.row(1).transpose(); M_jac2(0,0) += temp; temp = 2.0*R_jac2.row(1)*zzF*R.row(1).transpose(); M_jac2(0,0) += temp; temp = 2.0*R_jac3.row(2)*yyF*R.row(2).transpose(); M_jac3(0,0) = temp; temp = -2.0*R_jac3.row(2)*yzF*R.row(1).transpose(); M_jac3(0,0) += temp; temp = -2.0*R.row(2)*yzF*R_jac3.row(1).transpose(); M_jac3(0,0) += temp; temp = 2.0*R_jac3.row(1)*zzF*R.row(1).transpose(); M_jac3(0,0) += temp; temp = R.row(2)*yzF*R.row(0).transpose(); M(0,1) = temp; temp = -1.0*R.row(2)*xyF*R.row(2).transpose(); M(0,1) += temp; temp = -1.0*R.row(1)*zzF*R.row(0).transpose(); M(0,1) += temp; temp = R.row(1)*zxF*R.row(2).transpose(); M(0,1) += temp; temp = R_jac1.row(2)*yzF*R.row(0).transpose(); M_jac1(0,1) = temp; temp = R.row(2)*yzF*R_jac1.row(0).transpose(); M_jac1(0,1) += temp; temp = -2.0*R_jac1.row(2)*xyF*R.row(2).transpose(); M_jac1(0,1) += temp; temp = -R_jac1.row(1)*zzF*R.row(0).transpose(); M_jac1(0,1) += temp; temp = -R.row(1)*zzF*R_jac1.row(0).transpose(); M_jac1(0,1) += temp; temp = R_jac1.row(1)*zxF*R.row(2).transpose(); M_jac1(0,1) += temp; temp = R.row(1)*zxF*R_jac1.row(2).transpose(); M_jac1(0,1) += temp; temp = R_jac2.row(2)*yzF*R.row(0).transpose(); M_jac2(0,1) = temp; temp = R.row(2)*yzF*R_jac2.row(0).transpose(); M_jac2(0,1) += temp; temp = -2.0*R_jac2.row(2)*xyF*R.row(2).transpose(); M_jac2(0,1) += temp; temp = -R_jac2.row(1)*zzF*R.row(0).transpose(); M_jac2(0,1) += temp; temp = -R.row(1)*zzF*R_jac2.row(0).transpose(); M_jac2(0,1) += temp; temp = R_jac2.row(1)*zxF*R.row(2).transpose(); M_jac2(0,1) += temp; temp = R.row(1)*zxF*R_jac2.row(2).transpose(); M_jac2(0,1) += temp; temp = R_jac3.row(2)*yzF*R.row(0).transpose(); M_jac3(0,1) = temp; temp = R.row(2)*yzF*R_jac3.row(0).transpose(); M_jac3(0,1) += temp; temp = -2.0*R_jac3.row(2)*xyF*R.row(2).transpose(); M_jac3(0,1) += temp; temp = -R_jac3.row(1)*zzF*R.row(0).transpose(); M_jac3(0,1) += temp; temp = -R.row(1)*zzF*R_jac3.row(0).transpose(); M_jac3(0,1) += temp; temp = R_jac3.row(1)*zxF*R.row(2).transpose(); M_jac3(0,1) += temp; temp = R.row(1)*zxF*R_jac3.row(2).transpose(); M_jac3(0,1) += temp; temp = R.row(2)*xyF*R.row(1).transpose(); M(0,2) = temp; temp = -1.0*R.row(2)*yyF*R.row(0).transpose(); M(0,2) += temp; temp = -1.0*R.row(1)*zxF*R.row(1).transpose(); M(0,2) += temp; temp = R.row(1)*yzF*R.row(0).transpose(); M(0,2) += temp; temp = R_jac1.row(2)*xyF*R.row(1).transpose(); M_jac1(0,2) = temp; temp = R.row(2)*xyF*R_jac1.row(1).transpose(); M_jac1(0,2) += temp; temp = -R_jac1.row(2)*yyF*R.row(0).transpose(); M_jac1(0,2) += temp; temp = -R.row(2)*yyF*R_jac1.row(0).transpose(); M_jac1(0,2) += temp; temp = -2.0*R_jac1.row(1)*zxF*R.row(1).transpose(); M_jac1(0,2) += temp; temp = R_jac1.row(1)*yzF*R.row(0).transpose(); M_jac1(0,2) += temp; temp = R.row(1)*yzF*R_jac1.row(0).transpose(); M_jac1(0,2) += temp; temp = R_jac2.row(2)*xyF*R.row(1).transpose(); M_jac2(0,2) = temp; temp = R.row(2)*xyF*R_jac2.row(1).transpose(); M_jac2(0,2) += temp; temp = -R_jac2.row(2)*yyF*R.row(0).transpose(); M_jac2(0,2) += temp; temp = -R.row(2)*yyF*R_jac2.row(0).transpose(); M_jac2(0,2) += temp; temp = -2.0*R_jac2.row(1)*zxF*R.row(1).transpose(); M_jac2(0,2) += temp; temp = R_jac2.row(1)*yzF*R.row(0).transpose(); M_jac2(0,2) += temp; temp = R.row(1)*yzF*R_jac2.row(0).transpose(); M_jac2(0,2) += temp; temp = R_jac3.row(2)*xyF*R.row(1).transpose(); M_jac3(0,2) = temp; temp = R.row(2)*xyF*R_jac3.row(1).transpose(); M_jac3(0,2) += temp; temp = -R_jac3.row(2)*yyF*R.row(0).transpose(); M_jac3(0,2) += temp; temp = -R.row(2)*yyF*R_jac3.row(0).transpose(); M_jac3(0,2) += temp; temp = -2.0*R_jac3.row(1)*zxF*R.row(1).transpose(); M_jac3(0,2) += temp; temp = R_jac3.row(1)*yzF*R.row(0).transpose(); M_jac3(0,2) += temp; temp = R.row(1)*yzF*R_jac3.row(0).transpose(); M_jac3(0,2) += temp; temp = R.row(0)*zzF*R.row(0).transpose(); M(1,1) = temp; temp = -2.0*R.row(0)*zxF*R.row(2).transpose(); M(1,1) += temp; temp = R.row(2)*xxF*R.row(2).transpose(); M(1,1) += temp; temp = 2.0*R_jac1.row(0)*zzF*R.row(0).transpose(); M_jac1(1,1) = temp; temp = -2.0*R_jac1.row(0)*zxF*R.row(2).transpose(); M_jac1(1,1) += temp; temp = -2.0*R.row(0)*zxF*R_jac1.row(2).transpose(); M_jac1(1,1) += temp; temp = 2.0*R_jac1.row(2)*xxF*R.row(2).transpose(); M_jac1(1,1) += temp; temp = 2.0*R_jac2.row(0)*zzF*R.row(0).transpose(); M_jac2(1,1) = temp; temp = -2.0*R_jac2.row(0)*zxF*R.row(2).transpose(); M_jac2(1,1) += temp; temp = -2.0*R.row(0)*zxF*R_jac2.row(2).transpose(); M_jac2(1,1) += temp; temp = 2.0*R_jac2.row(2)*xxF*R.row(2).transpose(); M_jac2(1,1) += temp; temp = 2.0*R_jac3.row(0)*zzF*R.row(0).transpose(); M_jac3(1,1) = temp; temp = -2.0*R_jac3.row(0)*zxF*R.row(2).transpose(); M_jac3(1,1) += temp; temp = -2.0*R.row(0)*zxF*R_jac3.row(2).transpose(); M_jac3(1,1) += temp; temp = 2.0*R_jac3.row(2)*xxF*R.row(2).transpose(); M_jac3(1,1) += temp; temp = R.row(0)*zxF*R.row(1).transpose(); M(1,2) = temp; temp = -1.0*R.row(0)*yzF*R.row(0).transpose(); M(1,2) += temp; temp = -1.0*R.row(2)*xxF*R.row(1).transpose(); M(1,2) += temp; temp = R.row(2)*xyF*R.row(0).transpose(); M(1,2) += temp; temp = R_jac1.row(0)*zxF*R.row(1).transpose(); M_jac1(1,2) = temp; temp = R.row(0)*zxF*R_jac1.row(1).transpose(); M_jac1(1,2) += temp; temp = -2.0*R_jac1.row(0)*yzF*R.row(0).transpose(); M_jac1(1,2) += temp; temp = -R_jac1.row(2)*xxF*R.row(1).transpose(); M_jac1(1,2) += temp; temp = -R.row(2)*xxF*R_jac1.row(1).transpose(); M_jac1(1,2) += temp; temp = R_jac1.row(2)*xyF*R.row(0).transpose(); M_jac1(1,2) += temp; temp = R.row(2)*xyF*R_jac1.row(0).transpose(); M_jac1(1,2) += temp; temp = R_jac2.row(0)*zxF*R.row(1).transpose(); M_jac2(1,2) = temp; temp = R.row(0)*zxF*R_jac2.row(1).transpose(); M_jac2(1,2) += temp; temp = -2.0*R_jac2.row(0)*yzF*R.row(0).transpose(); M_jac2(1,2) += temp; temp = -R_jac2.row(2)*xxF*R.row(1).transpose(); M_jac2(1,2) += temp; temp = -R.row(2)*xxF*R_jac2.row(1).transpose(); M_jac2(1,2) += temp; temp = R_jac2.row(2)*xyF*R.row(0).transpose(); M_jac2(1,2) += temp; temp = R.row(2)*xyF*R_jac2.row(0).transpose(); M_jac2(1,2) += temp; temp = R_jac3.row(0)*zxF*R.row(1).transpose(); M_jac3(1,2) = temp; temp = R.row(0)*zxF*R_jac3.row(1).transpose(); M_jac3(1,2) += temp; temp = -2.0*R_jac3.row(0)*yzF*R.row(0).transpose(); M_jac3(1,2) += temp; temp = -R_jac3.row(2)*xxF*R.row(1).transpose(); M_jac3(1,2) += temp; temp = -R.row(2)*xxF*R_jac3.row(1).transpose(); M_jac3(1,2) += temp; temp = R_jac3.row(2)*xyF*R.row(0).transpose(); M_jac3(1,2) += temp; temp = R.row(2)*xyF*R_jac3.row(0).transpose(); M_jac3(1,2) += temp; temp = R.row(1)*xxF*R.row(1).transpose(); M(2,2) = temp; temp = -2.0*R.row(0)*xyF*R.row(1).transpose(); M(2,2) += temp; temp = R.row(0)*yyF*R.row(0).transpose(); M(2,2) += temp; temp = 2.0*R_jac1.row(1)*xxF*R.row(1).transpose(); M_jac1(2,2) = temp; temp = -2.0*R_jac1.row(0)*xyF*R.row(1).transpose(); M_jac1(2,2) += temp; temp = -2.0*R.row(0)*xyF*R_jac1.row(1).transpose(); M_jac1(2,2) += temp; temp = 2.0*R_jac1.row(0)*yyF*R.row(0).transpose(); M_jac1(2,2) += temp; temp = 2.0*R_jac2.row(1)*xxF*R.row(1).transpose(); M_jac2(2,2) = temp; temp = -2.0*R_jac2.row(0)*xyF*R.row(1).transpose(); M_jac2(2,2) += temp; temp = -2.0*R.row(0)*xyF*R_jac2.row(1).transpose(); M_jac2(2,2) += temp; temp = 2.0*R_jac2.row(0)*yyF*R.row(0).transpose(); M_jac2(2,2) += temp; temp = 2.0*R_jac3.row(1)*xxF*R.row(1).transpose(); M_jac3(2,2) = temp; temp = -2.0*R_jac3.row(0)*xyF*R.row(1).transpose(); M_jac3(2,2) += temp; temp = -2.0*R.row(0)*xyF*R_jac3.row(1).transpose(); M_jac3(2,2) += temp; temp = 2.0*R_jac3.row(0)*yyF*R.row(0).transpose(); M_jac3(2,2) += temp; M(1,0) = M(0,1); M(2,0) = M(0,2); M(2,1) = M(1,2); M_jac1(1,0) = M_jac1(0,1); M_jac1(2,0) = M_jac1(0,2); M_jac1(2,1) = M_jac1(1,2); M_jac2(1,0) = M_jac2(0,1); M_jac2(2,0) = M_jac2(0,2); M_jac2(2,1) = M_jac2(1,2); M_jac3(1,0) = M_jac3(0,1); M_jac3(2,0) = M_jac3(0,2); M_jac3(2,1) = M_jac3(1,2); return M; } opengv/src/relative_pose/modules/fivept_stewenius/0000775016516101651610000000000013344612246021512 5ustar dimadimaopengv/src/relative_pose/modules/fivept_stewenius/modules.cpp0000664016516101651610000022731513344612246023700 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::relative_pose::modules::fivept_stewenius::composeA( const Eigen::Matrix & EE, Eigen::Matrix & A) { double e00,e01,e02,e03,e04,e05,e06,e07,e08; double e10,e11,e12,e13,e14,e15,e16,e17,e18; double e20,e21,e22,e23,e24,e25,e26,e27,e28; double e30,e31,e32,e33,e34,e35,e36,e37,e38; double e002,e012,e022,e032,e042,e052,e062,e072,e082; double e102,e112,e122,e132,e142,e152,e162,e172,e182; double e202,e212,e222,e232,e242,e252,e262,e272,e282; double e302,e312,e322,e332,e342,e352,e362,e372,e382; double e003,e013,e023,e033,e043,e053,e063,e073,e083; double e103,e113,e123,e133,e143,e153,e163,e173,e183; double e203,e213,e223,e233,e243,e253,e263,e273,e283; double e303,e313,e323,e333,e343,e353,e363,e373,e383; e00 = EE(0,0); e10 = EE(0,1); e20 = EE(0,2); e30 = EE(0,3); e01 = EE(1,0); e11 = EE(1,1); e21 = EE(1,2); e31 = EE(1,3); e02 = EE(2,0); e12 = EE(2,1); e22 = EE(2,2); e32 = EE(2,3); e03 = EE(3,0); e13 = EE(3,1); e23 = EE(3,2); e33 = EE(3,3); e04 = EE(4,0); e14 = EE(4,1); e24 = EE(4,2); e34 = EE(4,3); e05 = EE(5,0); e15 = EE(5,1); e25 = EE(5,2); e35 = EE(5,3); e06 = EE(6,0); e16 = EE(6,1); e26 = EE(6,2); e36 = EE(6,3); e07 = EE(7,0); e17 = EE(7,1); e27 = EE(7,2); e37 = EE(7,3); e08 = EE(8,0); e18 = EE(8,1); e28 = EE(8,2); e38 = EE(8,3); e002 =e00*e00; e102 =e10*e10; e202 =e20*e20; e302 =e30*e30; e012 =e01*e01; e112 =e11*e11; e212 =e21*e21; e312 =e31*e31; e022 =e02*e02; e122 =e12*e12; e222 =e22*e22; e322 =e32*e32; e032 =e03*e03; e132 =e13*e13; e232 =e23*e23; e332 =e33*e33; e042 =e04*e04; e142 =e14*e14; e242 =e24*e24; e342 =e34*e34; e052 =e05*e05; e152 =e15*e15; e252 =e25*e25; e352 =e35*e35; e062 =e06*e06; e162 =e16*e16; e262 =e26*e26; e362 =e36*e36; e072 =e07*e07; e172 =e17*e17; e272 =e27*e27; e372 =e37*e37; e082 =e08*e08; e182 =e18*e18; e282 =e28*e28; e382 =e38*e38; e003 =e00*e00*e00; e103 =e10*e10*e10; e203 =e20*e20*e20; e303 =e30*e30*e30; e013 =e01*e01*e01; e113 =e11*e11*e11; e213 =e21*e21*e21; e313 =e31*e31*e31; e023 =e02*e02*e02; e123 =e12*e12*e12; e223 =e22*e22*e22; e323 =e32*e32*e32; e033 =e03*e03*e03; e133 =e13*e13*e13; e233 =e23*e23*e23; e333 =e33*e33*e33; e043 =e04*e04*e04; e143 =e14*e14*e14; e243 =e24*e24*e24; e343 =e34*e34*e34; e053 =e05*e05*e05; e153 =e15*e15*e15; e253 =e25*e25*e25; e353 =e35*e35*e35; e063 =e06*e06*e06; e163 =e16*e16*e16; e263 =e26*e26*e26; e363 =e36*e36*e36; e073 =e07*e07*e07; e173 =e17*e17*e17; e273 =e27*e27*e27; e373 =e37*e37*e37; e083 =e08*e08*e08; e183 =e18*e18*e18; e283 =e28*e28*e28; e383 =e38*e38*e38; A(0,0)=0.5*e003+0.5*e00*e012+0.5*e00*e022+0.5*e00*e032+e03*e01*e04+e03*e02*e05+0.5*e00*e062+e06*e01*e07+e06*e02*e08-0.5*e00*e042-0.5*e00*e052-0.5*e00*e072-0.5*e00*e082; A(0,1)=e00*e11*e01+e00*e12*e02+e03*e00*e13+e03*e11*e04+e03*e01*e14+e03*e12*e05+e03*e02*e15+e13*e01*e04+e13*e02*e05+e06*e00*e16+1.5*e10*e002+0.5*e10*e012+0.5*e10*e022+0.5*e10*e062-0.5*e10*e042-0.5*e10*e052-0.5*e10*e072+0.5*e10*e032+e06*e11*e07+e06*e01*e17+e06*e12*e08+e06*e02*e18+e16*e01*e07+e16*e02*e08-e00*e14*e04-e00*e17*e07-e00*e15*e05-e00*e18*e08-0.5*e10*e082; A(0,2)=e16*e02*e18+e03*e12*e15+e10*e11*e01+e10*e12*e02+e03*e10*e13+e03*e11*e14+e13*e11*e04+e13*e01*e14+e13*e12*e05+e13*e02*e15+e06*e10*e16+e06*e12*e18+e06*e11*e17+e16*e11*e07+e16*e01*e17+e16*e12*e08-e10*e14*e04-e10*e17*e07-e10*e15*e05-e10*e18*e08+1.5*e00*e102+0.5*e00*e122+0.5*e00*e112+0.5*e00*e132+0.5*e00*e162-0.5*e00*e152-0.5*e00*e172-0.5*e00*e182-0.5*e00*e142; A(0,3)=0.5*e103+0.5*e10*e122+0.5*e10*e112+0.5*e10*e132+e13*e12*e15+e13*e11*e14+0.5*e10*e162+e16*e12*e18+e16*e11*e17-0.5*e10*e152-0.5*e10*e172-0.5*e10*e182-0.5*e10*e142; A(0,4)=-e00*e28*e08-e00*e25*e05-e00*e27*e07-e00*e24*e04+e26*e02*e08+e26*e01*e07+e06*e02*e28+e06*e22*e08+e06*e01*e27+e06*e21*e07+e23*e02*e05+e23*e01*e04+e03*e02*e25+e03*e22*e05+e03*e01*e24+e03*e21*e04+e00*e22*e02+e00*e21*e01-0.5*e20*e082-0.5*e20*e052-0.5*e20*e072-0.5*e20*e042+e06*e00*e26+0.5*e20*e062+e03*e00*e23+0.5*e20*e022+1.5*e20*e002+0.5*e20*e032+0.5*e20*e012; A(0,5)=-e10*e24*e04-e10*e27*e07-e10*e25*e05-e10*e28*e08-e20*e14*e04-e20*e17*e07-e20*e15*e05-e20*e18*e08-e00*e24*e14-e00*e25*e15-e00*e27*e17-e00*e28*e18+e06*e21*e17+e06*e22*e18+e06*e12*e28+e16*e00*e26+e16*e21*e07+e16*e01*e27+e16*e22*e08+e16*e02*e28+e26*e11*e07+e26*e01*e17+e26*e12*e08+e26*e02*e18+e06*e11*e27+e23*e11*e04+e23*e01*e14+e23*e12*e05+e23*e02*e15+e06*e20*e16+e06*e10*e26+e03*e21*e14+e03*e22*e15+e03*e12*e25+e13*e00*e23+e13*e21*e04+e13*e01*e24+e13*e22*e05+e13*e02*e25+e03*e11*e24+e03*e20*e13+e03*e10*e23+e00*e21*e11+3*e00*e20*e10+e00*e22*e12+e20*e12*e02+e20*e11*e01+e10*e22*e02+e10*e21*e01; A(0,6)=-0.5*e20*e152+e26*e11*e17-e10*e24*e14-e10*e25*e15-e10*e27*e17-e10*e28*e18+0.5*e20*e162+e13*e10*e23+e13*e22*e15+e23*e12*e15+e23*e11*e14+e16*e10*e26+e16*e21*e17+e16*e11*e27+e16*e22*e18+e16*e12*e28+e26*e12*e18+e13*e12*e25+0.5*e20*e132+1.5*e20*e102+0.5*e20*e122+0.5*e20*e112+e10*e21*e11+e10*e22*e12+e13*e11*e24-0.5*e20*e172-0.5*e20*e182-0.5*e20*e142+e13*e21*e14; A(0,7)=-e20*e25*e05-e20*e28*e08-0.5*e00*e272-0.5*e00*e282-0.5*e00*e242+0.5*e00*e262-0.5*e00*e252+e06*e20*e26+0.5*e00*e232+e06*e22*e28+e06*e21*e27+e26*e21*e07+e26*e01*e27+e26*e22*e08+e26*e02*e28-e20*e24*e04-e20*e27*e07+e03*e20*e23+e03*e22*e25+e03*e21*e24+e23*e21*e04+e23*e01*e24+e23*e22*e05+e23*e02*e25+e20*e21*e01+e20*e22*e02+1.5*e00*e202+0.5*e00*e222+0.5*e00*e212; A(0,8)=e23*e21*e14+e23*e11*e24+e23*e22*e15+e23*e12*e25+e16*e20*e26+e16*e22*e28+e16*e21*e27+e26*e21*e17+e26*e11*e27+e26*e22*e18+e26*e12*e28+1.5*e10*e202+0.5*e10*e222+0.5*e10*e212+0.5*e10*e232+e20*e21*e11+e20*e22*e12+e13*e20*e23+e13*e22*e25+e13*e21*e24-e20*e24*e14-e20*e25*e15-e20*e27*e17-e20*e28*e18-0.5*e10*e272-0.5*e10*e282-0.5*e10*e242-0.5*e10*e252+0.5*e10*e262; A(0,9)=0.5*e203+0.5*e20*e222+0.5*e20*e212+0.5*e20*e232+e23*e22*e25+e23*e21*e24+0.5*e20*e262+e26*e22*e28+e26*e21*e27-0.5*e20*e252-0.5*e20*e272-0.5*e20*e282-0.5*e20*e242; A(0,10)=e06*e32*e08-0.5*e30*e082-0.5*e30*e042-0.5*e30*e052-0.5*e30*e072+0.5*e30*e012+0.5*e30*e022+0.5*e30*e032+0.5*e30*e062+1.5*e30*e002+e00*e31*e01+e00*e32*e02+e03*e31*e04+e03*e01*e34+e03*e32*e05+e03*e02*e35+e33*e01*e04+e33*e02*e05+e06*e00*e36+e06*e31*e07+e06*e01*e37+e06*e02*e38+e36*e01*e07+e36*e02*e08-e00*e34*e04-e00*e37*e07-e00*e35*e05-e00*e38*e08+e03*e00*e33; A(0,11)=e06*e30*e16+e03*e30*e13+e16*e31*e07+e06*e10*e36-e10*e37*e07+3*e00*e30*e10+e00*e32*e12-e00*e38*e18-e10*e34*e04-e10*e35*e05-e10*e38*e08-e30*e14*e04-e30*e17*e07-e30*e15*e05-e30*e18*e08+e00*e31*e11+e10*e31*e01+e10*e32*e02+e30*e11*e01+e30*e12*e02+e03*e10*e33-e00*e34*e14-e00*e35*e15-e00*e37*e17+e03*e31*e14+e03*e11*e34+e03*e32*e15+e03*e12*e35+e13*e00*e33+e13*e31*e04+e13*e01*e34+e13*e32*e05+e13*e02*e35+e33*e11*e04+e33*e01*e14+e33*e12*e05+e33*e02*e15+e06*e31*e17+e06*e11*e37+e06*e32*e18+e06*e12*e38+e16*e00*e36+e16*e01*e37+e16*e32*e08+e16*e02*e38+e36*e11*e07+e36*e01*e17+e36*e12*e08+e36*e02*e18; A(0,12)=e13*e10*e33+e33*e11*e14+e16*e10*e36+e16*e31*e17+e16*e11*e37+e16*e32*e18+e16*e12*e38+e36*e12*e18+e36*e11*e17-e10*e34*e14-e10*e35*e15-e10*e37*e17-e10*e38*e18+e10*e31*e11+e10*e32*e12+e13*e31*e14+e13*e11*e34+e13*e32*e15+e13*e12*e35+e33*e12*e15+1.5*e30*e102+0.5*e30*e122+0.5*e30*e112+0.5*e30*e132+0.5*e30*e162-0.5*e30*e152-0.5*e30*e172-0.5*e30*e182-0.5*e30*e142; A(0,13)=e00*e32*e22+3*e00*e30*e20+e00*e31*e21+e20*e31*e01+e20*e32*e02+e30*e21*e01+e30*e22*e02+e03*e20*e33+e03*e32*e25+e03*e22*e35+e03*e31*e24+e03*e21*e34+e23*e00*e33+e23*e31*e04+e23*e01*e34+e23*e32*e05+e23*e02*e35+e33*e21*e04+e33*e01*e24+e33*e22*e05+e33*e02*e25+e06*e30*e26+e06*e20*e36+e06*e32*e28+e06*e22*e38+e06*e31*e27+e06*e21*e37+e26*e00*e36+e26*e31*e07+e03*e30*e23+e26*e01*e37+e26*e32*e08+e26*e02*e38+e36*e21*e07+e36*e01*e27+e36*e22*e08+e36*e02*e28-e00*e35*e25-e00*e37*e27-e00*e38*e28-e00*e34*e24-e20*e34*e04-e20*e37*e07-e20*e35*e05-e20*e38*e08-e30*e24*e04-e30*e27*e07-e30*e25*e05-e30*e28*e08; A(0,14)=e16*e30*e26+e13*e21*e34+3*e10*e30*e20+e10*e32*e22+e10*e31*e21+e20*e31*e11+e20*e32*e12+e30*e21*e11+e30*e22*e12+e13*e30*e23+e13*e20*e33+e13*e32*e25+e13*e22*e35+e13*e31*e24+e23*e10*e33+e23*e31*e14+e23*e11*e34+e23*e32*e15+e23*e12*e35+e33*e21*e14+e33*e11*e24+e33*e22*e15+e33*e12*e25+e16*e20*e36+e16*e32*e28+e16*e22*e38+e16*e31*e27+e16*e21*e37+e26*e10*e36+e26*e31*e17+e26*e11*e37+e26*e32*e18+e26*e12*e38+e36*e21*e17+e36*e11*e27+e36*e22*e18+e36*e12*e28-e10*e35*e25-e10*e37*e27-e10*e38*e28-e10*e34*e24-e20*e34*e14-e20*e35*e15-e20*e37*e17-e20*e38*e18-e30*e24*e14-e30*e25*e15-e30*e27*e17-e30*e28*e18; A(0,15)=-e20*e34*e24+0.5*e30*e262-0.5*e30*e252-0.5*e30*e272-0.5*e30*e282-0.5*e30*e242+1.5*e30*e202+0.5*e30*e222+0.5*e30*e212+0.5*e30*e232+e20*e32*e22+e20*e31*e21+e23*e20*e33+e23*e32*e25+e23*e22*e35+e23*e31*e24+e23*e21*e34+e33*e22*e25+e33*e21*e24+e26*e20*e36+e26*e32*e28+e26*e22*e38+e26*e31*e27+e26*e21*e37+e36*e22*e28+e36*e21*e27-e20*e35*e25-e20*e37*e27-e20*e38*e28; A(0,16)=0.5*e00*e322+e30*e32*e02+e30*e31*e01+1.5*e00*e302+0.5*e00*e312+e03*e32*e35+e33*e31*e04+e33*e01*e34+e33*e32*e05+e33*e02*e35+e06*e30*e36+e06*e31*e37+e06*e32*e38+e36*e31*e07+e36*e01*e37+e36*e32*e08+e36*e02*e38-e30*e34*e04-e30*e37*e07-e30*e35*e05-e30*e38*e08+0.5*e00*e332+0.5*e00*e362-0.5*e00*e382-0.5*e00*e352-0.5*e00*e342-0.5*e00*e372+e03*e30*e33+e03*e31*e34; A(0,17)=0.5*e10*e362-0.5*e10*e382-0.5*e10*e352-0.5*e10*e342-0.5*e10*e372+e36*e31*e17+e36*e11*e37+e36*e32*e18+e36*e12*e38-e30*e34*e14-e30*e35*e15-e30*e37*e17-e30*e38*e18+1.5*e10*e302+0.5*e10*e312+0.5*e10*e322+0.5*e10*e332+e30*e31*e11+e30*e32*e12+e13*e30*e33+e13*e31*e34+e13*e32*e35+e33*e31*e14+e33*e11*e34+e33*e32*e15+e33*e12*e35+e16*e30*e36+e16*e31*e37+e16*e32*e38; A(0,18)=e33*e31*e24+e33*e21*e34+e26*e30*e36+e26*e31*e37+e26*e32*e38+e36*e32*e28+e36*e22*e38+e36*e31*e27+e36*e21*e37-e30*e35*e25-e30*e37*e27-e30*e38*e28-e30*e34*e24+e33*e22*e35+1.5*e20*e302+0.5*e20*e312+0.5*e20*e322+0.5*e20*e332+0.5*e20*e362-0.5*e20*e382-0.5*e20*e352-0.5*e20*e342-0.5*e20*e372+e30*e32*e22+e30*e31*e21+e23*e30*e33+e23*e31*e34+e23*e32*e35+e33*e32*e25; A(0,19)=0.5*e303+0.5*e30*e312+0.5*e30*e322+0.5*e30*e332+e33*e31*e34+e33*e32*e35+0.5*e30*e362+e36*e31*e37+e36*e32*e38-0.5*e30*e382-0.5*e30*e352-0.5*e30*e342-0.5*e30*e372; A(1,0)=e00*e01*e04+0.5*e002*e03+e00*e02*e05+0.5*e033+0.5*e03*e042+0.5*e03*e052+0.5*e03*e062+e06*e04*e07+e06*e05*e08-0.5*e03*e012-0.5*e03*e072-0.5*e03*e022-0.5*e03*e082; A(1,1)=e03*e14*e04+e10*e01*e04+e16*e05*e08+e00*e10*e03+e00*e11*e04+e00*e01*e14+e00*e12*e05+e00*e02*e15+e10*e02*e05+e03*e15*e05+e06*e03*e16+e06*e14*e07+e06*e04*e17+e06*e15*e08+e06*e05*e18+0.5*e002*e13+1.5*e13*e032+0.5*e13*e042+0.5*e13*e052+0.5*e13*e062-0.5*e13*e012-0.5*e13*e072-0.5*e13*e022-0.5*e13*e082+e16*e04*e07-e03*e12*e02-e03*e11*e01-e03*e17*e07-e03*e18*e08; A(1,2)=-e13*e11*e01+e00*e10*e13+e00*e12*e15+e00*e11*e14+e10*e11*e04+e10*e01*e14+e10*e12*e05+e10*e02*e15+e13*e14*e04+e13*e15*e05+e06*e13*e16+e06*e15*e18+e06*e14*e17+e16*e14*e07+e16*e04*e17+e16*e15*e08+e16*e05*e18-e13*e12*e02-e13*e17*e07-e13*e18*e08+0.5*e102*e03+1.5*e03*e132+0.5*e03*e152+0.5*e03*e142+0.5*e03*e162-0.5*e03*e112-0.5*e03*e172-0.5*e03*e122-0.5*e03*e182; A(1,3)=0.5*e102*e13+e10*e11*e14+e10*e12*e15+0.5*e133+0.5*e13*e152+0.5*e13*e142+0.5*e13*e162+e16*e15*e18+e16*e14*e17-0.5*e13*e112-0.5*e13*e122-0.5*e13*e172-0.5*e13*e182; A(1,4)=-e03*e28*e08-e03*e27*e07-e03*e21*e01-e03*e22*e02+e26*e05*e08+e26*e04*e07+e06*e05*e28+e06*e25*e08+e06*e04*e27+e06*e24*e07+e03*e25*e05+e03*e24*e04+e20*e02*e05+e20*e01*e04+e00*e02*e25+e00*e22*e05+e00*e01*e24+e00*e21*e04+e00*e20*e03-0.5*e23*e072-0.5*e23*e082-0.5*e23*e022-0.5*e23*e012+e06*e03*e26+0.5*e23*e052+0.5*e23*e062+1.5*e23*e032+0.5*e23*e042+0.5*e002*e23; A(1,5)=e00*e21*e14+e00*e11*e24+e00*e10*e23+e00*e22*e15+e00*e12*e25+e20*e12*e05+e20*e01*e14+e20*e11*e04+e00*e20*e13+e10*e02*e25+e10*e22*e05+e10*e01*e24+e10*e21*e04+e10*e20*e03+e23*e15*e05+e23*e14*e04+e13*e25*e05+e13*e24*e04+e03*e24*e14+e03*e25*e15+3*e03*e23*e13+e20*e02*e15+e16*e03*e26+e06*e14*e27-e23*e18*e08+e06*e24*e17+e06*e15*e28+e06*e25*e18+e06*e13*e26+e06*e23*e16+e26*e04*e17+e26*e14*e07+e16*e05*e28+e16*e25*e08+e16*e04*e27+e16*e24*e07-e03*e22*e12-e03*e21*e11+e26*e05*e18+e26*e15*e08-e03*e27*e17-e03*e28*e18-e13*e22*e02-e13*e28*e08-e13*e27*e07-e13*e21*e01-e23*e17*e07-e23*e11*e01-e23*e12*e02; A(1,6)=-0.5*e23*e182-0.5*e23*e172-0.5*e23*e112-0.5*e23*e122-e13*e22*e12-e13*e27*e17-e13*e28*e18+e26*e15*e18+e26*e14*e17-e13*e21*e11+e20*e12*e15+e13*e25*e15+e13*e24*e14+e16*e13*e26+e16*e25*e18+e16*e15*e28+e16*e24*e17+e16*e14*e27+1.5*e23*e132+0.5*e23*e152+0.5*e23*e142+0.5*e23*e162+e10*e20*e13+e10*e21*e14+e10*e11*e24+e10*e22*e15+e10*e12*e25+e20*e11*e14+0.5*e102*e23; A(1,7)=e26*e04*e27+e00*e22*e25-e23*e28*e08+0.5*e03*e262-0.5*e03*e212-0.5*e03*e272-0.5*e03*e222-0.5*e03*e282+e23*e24*e04+e23*e25*e05+0.5*e202*e03+e06*e23*e26+e06*e24*e27+e06*e25*e28+e26*e24*e07+e26*e25*e08+e26*e05*e28-e23*e22*e02-e23*e21*e01-e23*e27*e07+e00*e20*e23+e00*e21*e24+e20*e21*e04+e20*e01*e24+e20*e22*e05+e20*e02*e25+1.5*e03*e232+0.5*e03*e242+0.5*e03*e252; A(1,8)=e20*e11*e24-0.5*e13*e212-0.5*e13*e272-0.5*e13*e222-0.5*e13*e282-e23*e27*e17-e23*e28*e18+e26*e25*e18+e26*e24*e17+e26*e14*e27-e23*e21*e11-e23*e22*e12+e26*e15*e28+e23*e25*e15+e23*e24*e14+e16*e23*e26+e16*e24*e27+e16*e25*e28+0.5*e13*e262+e20*e21*e14+e20*e22*e15+e20*e12*e25+0.5*e13*e242+0.5*e13*e252+0.5*e202*e13+1.5*e13*e232+e10*e20*e23+e10*e22*e25+e10*e21*e24; A(1,9)=0.5*e202*e23+e20*e22*e25+e20*e21*e24+0.5*e233+0.5*e23*e242+0.5*e23*e252+0.5*e23*e262+e26*e24*e27+e26*e25*e28-0.5*e23*e212-0.5*e23*e272-0.5*e23*e222-0.5*e23*e282; A(1,10)=e00*e30*e03+0.5*e33*e062-0.5*e33*e012-0.5*e33*e022-0.5*e33*e072+e03*e35*e05+e06*e03*e36+e06*e34*e07+e06*e04*e37+e06*e35*e08+e06*e05*e38+e36*e04*e07+e36*e05*e08-e03*e32*e02-e03*e31*e01-e03*e37*e07+e00*e31*e04+e00*e01*e34+e00*e32*e05+e00*e02*e35+e30*e01*e04+e30*e02*e05+e03*e34*e04-e03*e38*e08+0.5*e002*e33+1.5*e33*e032+0.5*e33*e042+0.5*e33*e052-0.5*e33*e082; A(1,11)=e06*e35*e18+e06*e33*e16+e00*e30*e13+e00*e10*e33+e00*e31*e14+e00*e11*e34+e00*e32*e15+e00*e12*e35+e10*e30*e03-e33*e17*e07-e33*e18*e08+e10*e31*e04+e10*e01*e34+e10*e32*e05+e10*e02*e35+e30*e11*e04+e30*e01*e14+e30*e12*e05+e30*e02*e15+3*e03*e33*e13+e03*e35*e15+e03*e34*e14+e13*e34*e04+e13*e35*e05+e33*e14*e04+e33*e15*e05+e06*e13*e36+e06*e15*e38+e06*e34*e17+e06*e14*e37+e16*e03*e36+e16*e34*e07+e16*e04*e37+e16*e35*e08+e16*e05*e38+e36*e14*e07+e36*e04*e17+e36*e15*e08+e36*e05*e18-e03*e31*e11-e03*e32*e12-e03*e37*e17-e03*e38*e18-e13*e32*e02-e13*e31*e01-e13*e37*e07-e13*e38*e08-e33*e12*e02-e33*e11*e01; A(1,12)=e16*e13*e36+e10*e11*e34+0.5*e33*e152+0.5*e33*e142+0.5*e33*e162-0.5*e33*e112-0.5*e33*e122-0.5*e33*e172-0.5*e33*e182+0.5*e102*e33+1.5*e33*e132+e10*e30*e13+e10*e31*e14+e10*e32*e15+e10*e12*e35+e30*e11*e14+e30*e12*e15+e13*e35*e15+e13*e34*e14+e16*e35*e18+e16*e15*e38+e16*e34*e17+e16*e14*e37+e36*e15*e18+e36*e14*e17-e13*e31*e11-e13*e32*e12-e13*e37*e17-e13*e38*e18; A(1,13)=e06*e35*e28+e36*e04*e27+e00*e20*e33+e00*e30*e23+3*e03*e33*e23+e03*e34*e24+e03*e35*e25+e23*e34*e04+e23*e35*e05+e33*e24*e04+e33*e25*e05+e06*e33*e26+e06*e23*e36+e06*e34*e27+e06*e24*e37+e06*e25*e38+e26*e03*e36+e26*e34*e07+e26*e04*e37+e26*e35*e08+e26*e05*e38+e36*e24*e07+e36*e25*e08+e36*e05*e28-e03*e31*e21-e03*e37*e27-e03*e32*e22-e03*e38*e28-e23*e32*e02-e23*e31*e01-e23*e37*e07-e23*e38*e08-e33*e22*e02-e33*e21*e01-e33*e27*e07-e33*e28*e08+e00*e32*e25+e00*e22*e35+e00*e31*e24+e00*e21*e34+e20*e30*e03+e20*e31*e04+e20*e01*e34+e20*e32*e05+e20*e02*e35+e30*e21*e04+e30*e01*e24+e30*e22*e05+e30*e02*e25; A(1,14)=e10*e30*e23+e10*e20*e33+e10*e22*e35+e10*e32*e25+e10*e31*e24+e10*e21*e34+e20*e30*e13+e20*e31*e14+e20*e11*e34+e20*e32*e15+e20*e12*e35+e30*e21*e14+e30*e11*e24+e30*e22*e15+e30*e12*e25+3*e13*e33*e23+e13*e34*e24+e13*e35*e25+e23*e35*e15+e23*e34*e14+e33*e25*e15+e33*e24*e14+e16*e33*e26+e16*e23*e36+e16*e34*e27+e16*e24*e37+e16*e35*e28+e16*e25*e38+e26*e13*e36+e26*e35*e18+e26*e15*e38+e26*e34*e17+e26*e14*e37+e36*e25*e18+e36*e15*e28+e36*e24*e17+e36*e14*e27-e13*e31*e21-e13*e37*e27-e13*e32*e22-e13*e38*e28-e23*e31*e11-e23*e32*e12-e23*e37*e17-e23*e38*e18-e33*e21*e11-e33*e22*e12-e33*e27*e17-e33*e28*e18; A(1,15)=-0.5*e33*e212-0.5*e33*e272-0.5*e33*e222-0.5*e33*e282+e26*e23*e36+e20*e30*e23+e20*e32*e25+e20*e22*e35+e20*e31*e24+e20*e21*e34+e30*e22*e25+e30*e21*e24+e23*e34*e24+e23*e35*e25+e26*e34*e27+e26*e24*e37+e26*e35*e28+e26*e25*e38+e36*e24*e27+e36*e25*e28-e23*e31*e21-e23*e37*e27-e23*e32*e22-e23*e38*e28+0.5*e202*e33+1.5*e33*e232+0.5*e33*e242+0.5*e33*e252+0.5*e33*e262; A(1,16)=e33*e35*e05+e30*e32*e05+0.5*e03*e362+0.5*e302*e03+1.5*e03*e332+0.5*e03*e352+0.5*e03*e342+e00*e30*e33+e00*e31*e34+e00*e32*e35+e30*e31*e04+e30*e01*e34+e30*e02*e35+e33*e34*e04+e06*e33*e36+e06*e35*e38+e06*e34*e37+e36*e34*e07+e36*e04*e37+e36*e35*e08+e36*e05*e38-e33*e32*e02-e33*e31*e01-e33*e37*e07-e33*e38*e08-0.5*e03*e322-0.5*e03*e382-0.5*e03*e312-0.5*e03*e372; A(1,17)=-e33*e31*e11-e33*e32*e12-e33*e38*e18+e30*e11*e34+e30*e32*e15+e30*e12*e35+e33*e35*e15+e33*e34*e14+e16*e33*e36+e16*e35*e38+e16*e34*e37+e36*e35*e18+e36*e15*e38+e36*e34*e17+e36*e14*e37-e33*e37*e17+0.5*e302*e13+1.5*e13*e332+0.5*e13*e352+0.5*e13*e342+0.5*e13*e362-0.5*e13*e322-0.5*e13*e382-0.5*e13*e312-0.5*e13*e372+e10*e30*e33+e10*e31*e34+e10*e32*e35+e30*e31*e14; A(1,18)=e36*e25*e38+0.5*e302*e23+1.5*e23*e332+0.5*e23*e352+0.5*e23*e342+0.5*e23*e362-0.5*e23*e322-0.5*e23*e382-0.5*e23*e312-0.5*e23*e372+e20*e30*e33+e20*e31*e34+e20*e32*e35+e30*e32*e25+e30*e22*e35+e30*e31*e24+e30*e21*e34+e33*e34*e24+e33*e35*e25+e26*e33*e36+e26*e35*e38+e26*e34*e37+e36*e34*e27+e36*e24*e37+e36*e35*e28-e33*e31*e21-e33*e37*e27-e33*e32*e22-e33*e38*e28; A(1,19)=0.5*e302*e33+e30*e31*e34+e30*e32*e35+0.5*e333+0.5*e33*e352+0.5*e33*e342+0.5*e33*e362+e36*e35*e38+e36*e34*e37-0.5*e33*e322-0.5*e33*e382-0.5*e33*e312-0.5*e33*e372; A(2,0)=0.5*e002*e06+e00*e01*e07+e00*e02*e08+0.5*e032*e06+e03*e04*e07+e03*e05*e08+0.5*e063+0.5*e06*e072+0.5*e06*e082-0.5*e06*e012-0.5*e06*e022-0.5*e06*e042-0.5*e06*e052; A(2,1)=e00*e10*e06+0.5*e002*e16+0.5*e032*e16+1.5*e16*e062+0.5*e16*e072+0.5*e16*e082-0.5*e16*e012-0.5*e16*e022-0.5*e16*e042-0.5*e16*e052+e00*e11*e07+e00*e01*e17+e00*e12*e08+e00*e02*e18+e10*e01*e07+e10*e02*e08+e03*e13*e06+e03*e14*e07+e03*e04*e17+e03*e15*e08+e03*e05*e18+e13*e04*e07+e13*e05*e08+e06*e17*e07+e06*e18*e08-e06*e12*e02-e06*e11*e01-e06*e14*e04-e06*e15*e05; A(2,2)=e13*e14*e07+0.5*e102*e06+e00*e10*e16+e00*e12*e18+e00*e11*e17+e10*e11*e07+e10*e01*e17+e10*e12*e08+e10*e02*e18+e03*e13*e16+e03*e15*e18+e03*e14*e17+e13*e04*e17+e13*e15*e08+e13*e05*e18+e16*e17*e07+e16*e18*e08-e16*e12*e02-e16*e11*e01-e16*e14*e04-e16*e15*e05+0.5*e132*e06+1.5*e06*e162+0.5*e06*e182+0.5*e06*e172-0.5*e06*e112-0.5*e06*e122-0.5*e06*e142-0.5*e06*e152; A(2,3)=0.5*e102*e16+e10*e12*e18+e10*e11*e17+0.5*e132*e16+e13*e15*e18+e13*e14*e17+0.5*e163+0.5*e16*e182+0.5*e16*e172-0.5*e16*e112-0.5*e16*e122-0.5*e16*e142-0.5*e16*e152; A(2,4)=e06*e27*e07+e23*e05*e08+e23*e04*e07+e03*e05*e28+e03*e25*e08+e03*e04*e27+e03*e24*e07+e20*e02*e08+e20*e01*e07+e00*e02*e28+e00*e22*e08+e00*e01*e27+e00*e21*e07+e00*e20*e06-e06*e25*e05-e06*e24*e04-e06*e21*e01-e06*e22*e02+e06*e28*e08-0.5*e26*e042-0.5*e26*e052-0.5*e26*e012-0.5*e26*e022+0.5*e26*e082+0.5*e26*e072+1.5*e26*e062+0.5*e002*e26+e03*e23*e06+0.5*e032*e26; A(2,5)=e13*e05*e28+e00*e12*e28+e13*e25*e08+e13*e04*e27+e13*e24*e07+e13*e23*e06+e03*e14*e27+e03*e24*e17+e03*e15*e28+e03*e25*e18+e03*e13*e26+e03*e23*e16+e20*e02*e18+e20*e12*e08+e20*e01*e17+e20*e11*e07+e00*e21*e17+e10*e02*e28+e10*e22*e08+e10*e01*e27+e10*e21*e07+e10*e20*e06+e00*e11*e27-e26*e15*e05-e26*e14*e04-e26*e11*e01-e26*e12*e02-e16*e25*e05-e16*e24*e04-e16*e21*e01-e16*e22*e02-e06*e24*e14-e06*e22*e12-e06*e21*e11-e06*e25*e15+e00*e20*e16+e00*e22*e18+e00*e10*e26+e26*e18*e08+e26*e17*e07+e16*e28*e08+e16*e27*e07+e06*e27*e17+e06*e28*e18+3*e06*e26*e16+e23*e05*e18+e23*e15*e08+e23*e04*e17+e23*e14*e07; A(2,6)=e10*e22*e18+0.5*e26*e182+0.5*e26*e172+e16*e28*e18+e16*e27*e17-e16*e25*e15-e16*e21*e11-e16*e22*e12+1.5*e26*e162+e13*e15*e28+e13*e24*e17+e13*e14*e27+e23*e15*e18+e23*e14*e17+e10*e12*e28+e10*e21*e17+e10*e11*e27+e20*e12*e18+e20*e11*e17+e13*e23*e16+e13*e25*e18+e10*e20*e16+0.5*e102*e26-0.5*e26*e122-0.5*e26*e142-0.5*e26*e152-e16*e24*e14-0.5*e26*e112+0.5*e132*e26; A(2,7)=-0.5*e06*e212-0.5*e06*e252-0.5*e06*e242+0.5*e06*e272+0.5*e06*e282-0.5*e06*e222+e20*e02*e28+e03*e23*e26+e03*e24*e27+e03*e25*e28+e23*e24*e07+e23*e04*e27+e23*e25*e08+e23*e05*e28+e26*e28*e08-e26*e22*e02-e26*e21*e01-e26*e24*e04-e26*e25*e05+e26*e27*e07+e00*e20*e26+e00*e21*e27+e00*e22*e28+e20*e21*e07+e20*e01*e27+e20*e22*e08+0.5*e202*e06+0.5*e232*e06+1.5*e06*e262; A(2,8)=-e26*e24*e14-0.5*e16*e212-0.5*e16*e252-0.5*e16*e242-e26*e25*e15-0.5*e16*e222-e26*e21*e11+e26*e28*e18+e26*e27*e17-e26*e22*e12+e23*e15*e28+e23*e24*e17+e23*e14*e27+0.5*e232*e16+1.5*e16*e262+0.5*e16*e272+0.5*e16*e282+e10*e20*e26+e10*e21*e27+e10*e22*e28+e20*e22*e18+e20*e12*e28+e20*e21*e17+e20*e11*e27+e13*e23*e26+e13*e24*e27+e13*e25*e28+e23*e25*e18+0.5*e202*e16; A(2,9)=0.5*e202*e26+e20*e21*e27+e20*e22*e28+0.5*e232*e26+e23*e24*e27+e23*e25*e28+0.5*e263+0.5*e26*e272+0.5*e26*e282-0.5*e26*e222-0.5*e26*e212-0.5*e26*e252-0.5*e26*e242; A(2,10)=e03*e34*e07+0.5*e032*e36+1.5*e36*e062+e03*e33*e06+e00*e31*e07+e00*e01*e37+e00*e32*e08+e00*e02*e38+e30*e01*e07+e30*e02*e08+e03*e04*e37+e03*e35*e08+e03*e05*e38+0.5*e002*e36-0.5*e36*e022-0.5*e36*e042-0.5*e36*e052+0.5*e36*e072+0.5*e36*e082-0.5*e36*e012+e33*e04*e07+e33*e05*e08+e06*e37*e07+e06*e38*e08-e06*e32*e02-e06*e31*e01-e06*e34*e04-e06*e35*e05+e00*e30*e06; A(2,11)=e13*e33*e06+e13*e34*e07+e13*e04*e37+e13*e35*e08+e13*e05*e38+e33*e14*e07+e33*e04*e17+e33*e15*e08+e33*e05*e18+3*e06*e36*e16+e06*e38*e18+e06*e37*e17+e16*e37*e07+e16*e38*e08+e36*e17*e07+e36*e18*e08-e06*e35*e15-e06*e31*e11-e06*e32*e12+e00*e31*e17+e00*e11*e37+e10*e30*e06+e10*e31*e07+e10*e01*e37+e10*e32*e08+e10*e02*e38+e30*e11*e07+e30*e01*e17+e30*e12*e08+e30*e02*e18+e03*e33*e16+e03*e13*e36+e03*e35*e18+e03*e15*e38+e03*e34*e17+e03*e14*e37+e00*e30*e16+e00*e12*e38-e06*e34*e14-e16*e32*e02-e16*e31*e01-e16*e34*e04-e16*e35*e05-e36*e12*e02-e36*e11*e01-e36*e14*e04-e36*e15*e05+e00*e10*e36+e00*e32*e18; A(2,12)=0.5*e36*e182+0.5*e36*e172-0.5*e36*e112-0.5*e36*e122-0.5*e36*e142-0.5*e36*e152+0.5*e102*e36+0.5*e132*e36+1.5*e36*e162+e10*e30*e16+e10*e32*e18+e10*e12*e38+e10*e31*e17+e10*e11*e37+e30*e12*e18+e30*e11*e17+e13*e33*e16+e13*e35*e18+e13*e15*e38+e13*e34*e17+e13*e14*e37+e33*e15*e18+e33*e14*e17+e16*e38*e18+e16*e37*e17-e16*e35*e15-e16*e31*e11-e16*e32*e12-e16*e34*e14; A(2,13)=e00*e20*e36+e00*e31*e27+e00*e21*e37+e00*e32*e28+e00*e22*e38+e20*e30*e06+e20*e31*e07+e20*e01*e37+e20*e32*e08+e20*e02*e38+e30*e21*e07+e30*e01*e27+e30*e22*e08+e30*e02*e28+e03*e33*e26+e03*e23*e36+e03*e34*e27+e03*e24*e37+e03*e35*e28-e26*e31*e01-e26*e35*e05-e36*e22*e02-e36*e21*e01-e36*e24*e04-e36*e25*e05-e26*e34*e04+e03*e25*e38+e23*e34*e07+e23*e04*e37+e23*e35*e08+e23*e05*e38+e33*e24*e07+e33*e04*e27+e33*e25*e08+e33*e05*e28+3*e06*e36*e26+e06*e37*e27+e06*e38*e28+e26*e37*e07+e26*e38*e08+e36*e27*e07+e36*e28*e08-e06*e32*e22-e06*e31*e21-e06*e35*e25-e06*e34*e24-e26*e32*e02+e00*e30*e26+e23*e33*e06; A(2,14)=e10*e30*e26+e10*e20*e36+e10*e31*e27+e10*e21*e37+e10*e32*e28+e10*e22*e38+e20*e30*e16+e20*e32*e18+e20*e12*e38+e20*e31*e17+e20*e11*e37+e30*e22*e18+e30*e12*e28+e30*e21*e17+e30*e11*e27+e13*e33*e26+e13*e23*e36+e13*e34*e27+e13*e24*e37+e13*e35*e28+e13*e25*e38+e23*e33*e16+e23*e35*e18+e23*e15*e38+e23*e34*e17+e23*e14*e37+e33*e25*e18+e33*e15*e28+e33*e24*e17+e33*e14*e27+3*e16*e36*e26+e16*e37*e27+e16*e38*e28+e26*e38*e18+e26*e37*e17+e36*e28*e18+e36*e27*e17-e16*e32*e22-e16*e31*e21-e16*e35*e25-e16*e34*e24-e26*e35*e15-e26*e31*e11-e26*e32*e12-e26*e34*e14-e36*e25*e15-e36*e21*e11-e36*e22*e12-e36*e24*e14; A(2,15)=e33*e25*e28+e20*e30*e26+e20*e32*e28+e20*e31*e27+e20*e21*e37+e20*e22*e38+e30*e21*e27+e30*e22*e28+e23*e33*e26+e23*e34*e27+e23*e24*e37+e23*e35*e28+e23*e25*e38+e33*e24*e27+e26*e37*e27+e26*e38*e28-e26*e32*e22-e26*e31*e21-e26*e35*e25-e26*e34*e24+0.5*e202*e36+0.5*e232*e36+1.5*e36*e262+0.5*e36*e272+0.5*e36*e282-0.5*e36*e222-0.5*e36*e212-0.5*e36*e252-0.5*e36*e242; A(2,16)=e00*e30*e36+e00*e32*e38+e00*e31*e37+e30*e31*e07+e30*e01*e37+e30*e32*e08+e30*e02*e38+e03*e33*e36-0.5*e06*e342+e03*e35*e38+e33*e34*e07+e33*e04*e37+e33*e35*e08+e33*e05*e38+e36*e37*e07+e36*e38*e08-e36*e32*e02-e36*e31*e01-e36*e34*e04-e36*e35*e05+e03*e34*e37+0.5*e302*e06+0.5*e332*e06+1.5*e06*e362+0.5*e06*e382+0.5*e06*e372-0.5*e06*e352-0.5*e06*e312-0.5*e06*e322; A(2,17)=-e36*e35*e15+e10*e30*e36+0.5*e302*e16+0.5*e332*e16+1.5*e16*e362+0.5*e16*e382+0.5*e16*e372-0.5*e16*e352-0.5*e16*e312-0.5*e16*e322-0.5*e16*e342+e10*e32*e38+e10*e31*e37+e30*e32*e18+e30*e12*e38+e30*e31*e17+e30*e11*e37+e13*e33*e36+e13*e35*e38+e13*e34*e37+e33*e35*e18+e33*e15*e38+e33*e34*e17+e33*e14*e37+e36*e38*e18+e36*e37*e17-e36*e31*e11-e36*e32*e12-e36*e34*e14; A(2,18)=-e36*e35*e25+e30*e32*e28+0.5*e302*e26+0.5*e332*e26+1.5*e26*e362+0.5*e26*e382+0.5*e26*e372-0.5*e26*e352-0.5*e26*e312-0.5*e26*e322-0.5*e26*e342+e20*e30*e36+e20*e32*e38+e20*e31*e37+e30*e31*e27+e30*e21*e37+e30*e22*e38+e23*e33*e36+e23*e35*e38+e23*e34*e37+e33*e34*e27+e33*e24*e37+e33*e35*e28+e33*e25*e38+e36*e37*e27+e36*e38*e28-e36*e32*e22-e36*e31*e21-e36*e34*e24; A(2,19)=0.5*e302*e36+e30*e32*e38+e30*e31*e37+0.5*e332*e36+e33*e35*e38+e33*e34*e37+0.5*e363+0.5*e36*e382+0.5*e36*e372-0.5*e36*e352-0.5*e36*e312-0.5*e36*e322-0.5*e36*e342; A(3,0)=0.5*e01*e002+0.5*e013+0.5*e01*e022+e04*e00*e03+0.5*e01*e042+e04*e02*e05+e07*e00*e06+0.5*e01*e072+e07*e02*e08-0.5*e01*e032-0.5*e01*e052-0.5*e01*e062-0.5*e01*e082; A(3,1)=1.5*e11*e012+0.5*e11*e002+0.5*e11*e022+0.5*e11*e042+0.5*e11*e072-0.5*e11*e032-0.5*e11*e052-0.5*e11*e062-0.5*e11*e082+e01*e10*e00+e01*e12*e02+e04*e10*e03+e04*e00*e13+e04*e01*e14+e04*e12*e05+e04*e02*e15+e14*e00*e03+e14*e02*e05+e07*e10*e06+e07*e00*e16+e07*e01*e17+e07*e12*e08+e07*e02*e18+e17*e00*e06+e17*e02*e08-e01*e13*e03-e01*e16*e06-e01*e15*e05-e01*e18*e08; A(3,2)=e17*e02*e18+e14*e10*e03+e11*e12*e02-e11*e18*e08+0.5*e01*e102+0.5*e01*e122+1.5*e01*e112+0.5*e01*e142+0.5*e01*e172-0.5*e01*e132-0.5*e01*e152-0.5*e01*e162-0.5*e01*e182+e11*e10*e00+e04*e10*e13+e04*e12*e15+e04*e11*e14+e14*e00*e13+e14*e12*e05+e14*e02*e15+e07*e10*e16+e07*e12*e18+e07*e11*e17+e17*e10*e06+e17*e00*e16+e17*e12*e08-e11*e13*e03-e11*e16*e06-e11*e15*e05; A(3,3)=0.5*e11*e102+0.5*e11*e122+0.5*e113+e14*e10*e13+e14*e12*e15+0.5*e11*e142+e17*e10*e16+e17*e12*e18+0.5*e11*e172-0.5*e11*e132-0.5*e11*e152-0.5*e11*e162-0.5*e11*e182; A(3,4)=-e01*e25*e05-e01*e26*e06-e01*e23*e03+e27*e02*e08+e27*e00*e06+e07*e02*e28+e07*e22*e08+e07*e01*e27+e07*e00*e26+e24*e02*e05+e24*e00*e03+e04*e02*e25+e04*e22*e05+e04*e01*e24+e04*e00*e23+e04*e20*e03+e01*e22*e02+e01*e20*e00-e01*e28*e08+e07*e20*e06+0.5*e21*e072+0.5*e21*e042+0.5*e21*e022+0.5*e21*e002+1.5*e21*e012-0.5*e21*e082-0.5*e21*e052-0.5*e21*e062-0.5*e21*e032; A(3,5)=e11*e20*e00+e07*e20*e16+3*e01*e21*e11+e01*e22*e12-e21*e18*e08-e21*e15*e05-e21*e16*e06-e21*e13*e03-e11*e28*e08-e11*e25*e05-e11*e26*e06-e11*e23*e03-e01*e28*e18-e01*e23*e13-e01*e25*e15-e01*e26*e16+e27*e02*e18+e27*e12*e08+e27*e00*e16+e27*e10*e06+e17*e02*e28+e17*e22*e08+e17*e01*e27+e17*e00*e26+e17*e20*e06+e07*e11*e27+e07*e21*e17+e07*e12*e28+e07*e22*e18+e07*e10*e26+e24*e02*e15+e24*e12*e05+e24*e00*e13+e24*e10*e03+e14*e02*e25+e14*e22*e05+e14*e01*e24+e14*e00*e23+e14*e20*e03+e04*e11*e24+e04*e21*e14+e04*e12*e25+e04*e22*e15+e21*e12*e02+e04*e20*e13+e01*e20*e10+e11*e22*e02+e21*e10*e00+e04*e10*e23; A(3,6)=1.5*e21*e112+0.5*e21*e102+0.5*e21*e122+e11*e20*e10+e11*e22*e12+e14*e10*e23+e14*e22*e15+e14*e12*e25-0.5*e21*e162-0.5*e21*e152-0.5*e21*e132-0.5*e21*e182+e27*e12*e18-e11*e26*e16-e11*e25*e15-e11*e23*e13-e11*e28*e18+e17*e20*e16+e17*e10*e26+e17*e22*e18+e17*e12*e28+e17*e11*e27+e27*e10*e16+0.5*e21*e172+e14*e11*e24+e24*e10*e13+e24*e12*e15+0.5*e21*e142+e14*e20*e13; A(3,7)=-0.5*e01*e262-0.5*e01*e282-0.5*e01*e252-0.5*e01*e232+0.5*e01*e272+e27*e22*e08+e27*e02*e28-e21*e23*e03-e21*e26*e06-e21*e25*e05-e21*e28*e08+e04*e22*e25+e24*e20*e03+e24*e00*e23+e24*e22*e05+e24*e02*e25+e07*e20*e26+e07*e21*e27+e07*e22*e28+e27*e20*e06+e27*e00*e26+e21*e20*e00+e21*e22*e02+e04*e20*e23+e04*e21*e24+0.5*e01*e222+0.5*e01*e242+1.5*e01*e212+0.5*e01*e202; A(3,8)=-0.5*e11*e282-0.5*e11*e252-e21*e26*e16+e27*e12*e28-e21*e25*e15-e21*e23*e13-e21*e28*e18+e17*e20*e26+e17*e21*e27+e17*e22*e28+e27*e20*e16+e27*e10*e26+e27*e22*e18+0.5*e11*e242+0.5*e11*e272-0.5*e11*e232-0.5*e11*e262+0.5*e11*e202+1.5*e11*e212+0.5*e11*e222+e21*e20*e10+e14*e20*e23+e14*e21*e24+e14*e22*e25+e24*e20*e13+e24*e10*e23+e24*e22*e15+e24*e12*e25+e21*e22*e12; A(3,9)=0.5*e21*e202+0.5*e213+0.5*e21*e222+e24*e20*e23+0.5*e21*e242+e24*e22*e25+e27*e20*e26+0.5*e21*e272+e27*e22*e28-0.5*e21*e232-0.5*e21*e262-0.5*e21*e282-0.5*e21*e252; A(3,10)=-0.5*e31*e032-0.5*e31*e052-0.5*e31*e062-0.5*e31*e082+e07*e30*e06+e07*e00*e36+e07*e01*e37+e07*e32*e08+e07*e02*e38+e37*e00*e06+e37*e02*e08-e01*e33*e03-e01*e36*e06-e01*e35*e05-e01*e38*e08+0.5*e31*e072+e04*e30*e03+e04*e00*e33+e04*e01*e34+e04*e32*e05+e04*e02*e35+e34*e00*e03+e34*e02*e05+0.5*e31*e002+0.5*e31*e022+0.5*e31*e042+e01*e30*e00+e01*e32*e02+1.5*e31*e012; A(3,11)=e34*e12*e05+e34*e02*e15+e07*e10*e36+e07*e32*e18+e07*e12*e38+e07*e31*e17+e07*e11*e37+e17*e30*e06+e17*e00*e36+e17*e01*e37+e17*e32*e08+e17*e02*e38+e37*e10*e06+e37*e00*e16+e37*e12*e08+e37*e02*e18-e01*e36*e16-e01*e35*e15-e01*e33*e13-e01*e38*e18-e11*e33*e03-e11*e36*e06-e11*e35*e05+e01*e30*e10+e01*e32*e12+3*e01*e31*e11+e11*e30*e00+e11*e32*e02+e31*e10*e00+e31*e12*e02+e04*e30*e13+e04*e10*e33+e04*e32*e15+e04*e12*e35+e04*e31*e14+e04*e11*e34+e14*e30*e03+e14*e00*e33+e14*e01*e34+e14*e32*e05+e14*e02*e35+e34*e10*e03+e34*e00*e13+e07*e30*e16-e11*e38*e08-e31*e13*e03-e31*e16*e06-e31*e15*e05-e31*e18*e08; A(3,12)=-e11*e33*e13-e11*e38*e18+0.5*e31*e142+0.5*e31*e172-0.5*e31*e162-0.5*e31*e152-0.5*e31*e132-0.5*e31*e182+0.5*e31*e122+0.5*e31*e102+e11*e30*e10+e11*e32*e12+e14*e30*e13+e14*e10*e33+e14*e32*e15+e14*e12*e35+e14*e11*e34+e34*e10*e13+e34*e12*e15+e17*e30*e16+e17*e10*e36+e17*e32*e18+e17*e12*e38+e17*e11*e37+e37*e10*e16+e37*e12*e18-e11*e36*e16-e11*e35*e15+1.5*e31*e112; A(3,13)=-e21*e35*e05+e07*e32*e28+e01*e30*e20-e21*e33*e03-e21*e36*e06-e21*e38*e08-e31*e23*e03-e31*e26*e06-e31*e25*e05-e31*e28*e08+3*e01*e31*e21+e01*e32*e22+e21*e30*e00+e21*e32*e02+e31*e20*e00+e31*e22*e02+e04*e30*e23+e04*e20*e33+e04*e31*e24+e04*e21*e34+e04*e32*e25+e04*e22*e35+e24*e30*e03+e24*e00*e33+e24*e01*e34+e24*e32*e05+e24*e02*e35+e34*e20*e03+e34*e00*e23+e34*e22*e05+e34*e02*e25+e07*e30*e26+e07*e20*e36+e07*e31*e27+e07*e21*e37+e07*e22*e38+e27*e30*e06+e27*e00*e36+e27*e01*e37+e27*e32*e08+e27*e02*e38+e37*e00*e26+e37*e22*e08+e37*e02*e28-e01*e33*e23-e01*e36*e26-e01*e38*e28-e01*e35*e25+e37*e20*e06; A(3,14)=e11*e32*e22+e34*e12*e25+e11*e30*e20+3*e11*e31*e21+e21*e30*e10+e21*e32*e12+e34*e10*e23+e34*e22*e15+e17*e30*e26+e17*e20*e36+e17*e31*e27+e17*e21*e37+e17*e32*e28+e17*e22*e38+e27*e30*e16+e27*e10*e36+e27*e32*e18+e27*e12*e38+e27*e11*e37+e37*e20*e16+e37*e10*e26+e37*e22*e18+e37*e12*e28-e11*e33*e23-e11*e36*e26-e11*e38*e28-e11*e35*e25-e21*e36*e16-e21*e35*e15-e21*e33*e13-e21*e38*e18-e31*e26*e16-e31*e25*e15-e31*e23*e13-e31*e28*e18+e31*e20*e10+e31*e22*e12+e14*e30*e23+e14*e20*e33+e14*e31*e24+e14*e21*e34+e14*e32*e25+e14*e22*e35+e24*e30*e13+e24*e10*e33+e24*e32*e15+e24*e12*e35+e24*e11*e34+e34*e20*e13; A(3,15)=-e21*e36*e26+e37*e22*e28-e21*e33*e23-e21*e38*e28-e21*e35*e25+0.5*e31*e222+0.5*e31*e242+0.5*e31*e272-0.5*e31*e232-0.5*e31*e262-0.5*e31*e282-0.5*e31*e252+e21*e30*e20+e21*e32*e22+e24*e30*e23+e24*e20*e33+e24*e21*e34+e24*e32*e25+e24*e22*e35+e34*e20*e23+e34*e22*e25+e27*e30*e26+e27*e20*e36+e27*e21*e37+e27*e32*e28+e27*e22*e38+e37*e20*e26+1.5*e31*e212+0.5*e31*e202; A(3,16)=e04*e32*e35+0.5*e01*e372-0.5*e01*e352-0.5*e01*e362-0.5*e01*e332-0.5*e01*e382+e04*e31*e34+e34*e30*e03+e34*e00*e33+e34*e32*e05+e34*e02*e35+e07*e30*e36+e07*e32*e38+e07*e31*e37+e37*e30*e06+e37*e00*e36+e37*e32*e08+e04*e30*e33+e37*e02*e38-e31*e33*e03-e31*e36*e06-e31*e35*e05-e31*e38*e08+0.5*e01*e302+0.5*e01*e322+1.5*e01*e312+0.5*e01*e342+e31*e30*e00+e31*e32*e02; A(3,17)=e31*e32*e12+e14*e30*e33+e14*e32*e35+e14*e31*e34+e34*e30*e13+e34*e10*e33+e34*e32*e15+e34*e12*e35+e17*e30*e36+e17*e32*e38+e17*e31*e37+e37*e30*e16+e37*e10*e36+e37*e32*e18+e37*e12*e38-e31*e36*e16-e31*e35*e15+0.5*e11*e302+0.5*e11*e322+1.5*e11*e312-e31*e33*e13-e31*e38*e18+0.5*e11*e342+0.5*e11*e372+e31*e30*e10-0.5*e11*e352-0.5*e11*e362-0.5*e11*e332-0.5*e11*e382; A(3,18)=e34*e32*e25+0.5*e21*e342+0.5*e21*e372-0.5*e21*e352-0.5*e21*e362-0.5*e21*e332-0.5*e21*e382+0.5*e21*e302+0.5*e21*e322+1.5*e21*e312+e31*e30*e20+e31*e32*e22+e24*e30*e33+e24*e32*e35+e24*e31*e34+e34*e30*e23+e34*e20*e33+e34*e22*e35+e27*e30*e36+e27*e32*e38+e27*e31*e37+e37*e30*e26+e37*e20*e36+e37*e32*e28+e37*e22*e38-e31*e33*e23-e31*e36*e26-e31*e38*e28-e31*e35*e25; A(3,19)=0.5*e31*e302+0.5*e31*e322+0.5*e313+e34*e30*e33+e34*e32*e35+0.5*e31*e342+e37*e30*e36+e37*e32*e38+0.5*e31*e372-0.5*e31*e352-0.5*e31*e362-0.5*e31*e332-0.5*e31*e382; A(4,0)=e01*e00*e03+0.5*e012*e04+e01*e02*e05+0.5*e04*e032+0.5*e043+0.5*e04*e052+e07*e03*e06+0.5*e04*e072+e07*e05*e08-0.5*e04*e002-0.5*e04*e022-0.5*e04*e062-0.5*e04*e082; A(4,1)=e07*e13*e06+e01*e10*e03-0.5*e14*e002-0.5*e14*e022-0.5*e14*e062-0.5*e14*e082+e01*e00*e13+e01*e11*e04+e01*e12*e05+e01*e02*e15+e11*e00*e03+e11*e02*e05+e04*e13*e03+e04*e15*e05+e07*e03*e16+e07*e04*e17+e07*e15*e08+e07*e05*e18+e17*e03*e06+e17*e05*e08-e04*e10*e00-e04*e12*e02-e04*e16*e06-e04*e18*e08+0.5*e012*e14+1.5*e14*e042+0.5*e14*e032+0.5*e14*e052+0.5*e14*e072; A(4,2)=e11*e10*e03+0.5*e112*e04+0.5*e04*e132+0.5*e04*e152+1.5*e04*e142+0.5*e04*e172-0.5*e04*e102-0.5*e04*e162-0.5*e04*e122-0.5*e04*e182+e01*e10*e13+e01*e12*e15+e01*e11*e14+e11*e00*e13+e11*e12*e05+e11*e02*e15+e14*e13*e03+e14*e15*e05+e07*e13*e16+e07*e15*e18+e07*e14*e17+e17*e13*e06+e17*e03*e16+e17*e15*e08+e17*e05*e18-e14*e10*e00-e14*e12*e02-e14*e16*e06-e14*e18*e08; A(4,3)=e11*e10*e13+e11*e12*e15+0.5*e112*e14+0.5*e14*e132+0.5*e14*e152+0.5*e143+e17*e13*e16+e17*e15*e18+0.5*e14*e172-0.5*e14*e102-0.5*e14*e162-0.5*e14*e122-0.5*e14*e182; A(4,4)=-e04*e28*e08-e04*e26*e06-e04*e22*e02-e04*e20*e00+e27*e05*e08+e27*e03*e06+e07*e05*e28+e07*e25*e08+e07*e04*e27+e07*e03*e26+e07*e23*e06+e04*e25*e05+e04*e23*e03+e21*e02*e05+e21*e00*e03+e01*e02*e25+e01*e22*e05+e01*e21*e04+e01*e00*e23+e01*e20*e03+0.5*e012*e24+0.5*e24*e072+0.5*e24*e052+0.5*e24*e032+1.5*e24*e042-0.5*e24*e022-0.5*e24*e002-0.5*e24*e082-0.5*e24*e062; A(4,5)=e11*e02*e25+e11*e22*e05+e11*e21*e04-e24*e18*e08-e24*e16*e06-e24*e12*e02-e14*e28*e08-e14*e26*e06-e14*e22*e02-e14*e20*e00-e04*e28*e18-e04*e22*e12-e04*e26*e16-e04*e20*e10+e27*e05*e18+e27*e15*e08+e27*e03*e16+e27*e13*e06+e17*e05*e28+e17*e25*e08+e17*e04*e27+e17*e03*e26+e17*e23*e06+e07*e14*e27+e07*e24*e17+e07*e15*e28+e07*e25*e18+e07*e13*e26+e07*e23*e16+e24*e15*e05+e24*e13*e03+e14*e25*e05+e14*e23*e03+3*e04*e24*e14+e04*e25*e15+e04*e23*e13+e21*e02*e15+e21*e12*e05+e21*e00*e13+e21*e10*e03-e24*e10*e00+e01*e20*e13+e01*e10*e23+e01*e22*e15+e01*e12*e25+e01*e11*e24+e11*e20*e03+e11*e00*e23+e01*e21*e14; A(4,6)=e11*e12*e25-0.5*e24*e182-0.5*e24*e102-0.5*e24*e162-0.5*e24*e122+e27*e13*e16+e27*e15*e18-e14*e20*e10-e14*e26*e16-e14*e22*e12-e14*e28*e18+e17*e15*e28+e17*e14*e27+1.5*e24*e142+0.5*e24*e132+0.5*e24*e152+0.5*e112*e24+0.5*e24*e172+e11*e21*e14+e11*e22*e15+e11*e10*e23+e11*e20*e13+e21*e10*e13+e21*e12*e15+e17*e13*e26+e17*e23*e16+e14*e25*e15+e14*e23*e13+e17*e25*e18; A(4,7)=e27*e03*e26+e27*e25*e08+e27*e05*e28-e24*e20*e00-e24*e22*e02-e24*e26*e06-e24*e28*e08+0.5*e04*e232+1.5*e04*e242+0.5*e04*e252+0.5*e04*e272-0.5*e04*e202-0.5*e04*e222-0.5*e04*e262-0.5*e04*e282+e24*e23*e03+e24*e25*e05+e07*e23*e26+e07*e24*e27+e07*e25*e28+e27*e23*e06+e21*e20*e03+e21*e00*e23+e21*e22*e05+e21*e02*e25+0.5*e212*e04+e01*e20*e23+e01*e21*e24+e01*e22*e25; A(4,8)=-e24*e22*e12-e24*e28*e18+0.5*e14*e272-0.5*e14*e202-0.5*e14*e222-0.5*e14*e262-0.5*e14*e282+e17*e23*e26+e17*e24*e27+e17*e25*e28+e27*e23*e16+e27*e13*e26+e27*e25*e18+e27*e15*e28-e24*e20*e10-e24*e26*e16+0.5*e14*e232+1.5*e14*e242+0.5*e14*e252+e21*e10*e23+e21*e22*e15+e21*e12*e25+e24*e23*e13+e24*e25*e15+e21*e20*e13+0.5*e212*e14+e11*e20*e23+e11*e22*e25+e11*e21*e24; A(4,9)=e21*e20*e23+0.5*e212*e24+e21*e22*e25+0.5*e24*e232+0.5*e243+0.5*e24*e252+e27*e23*e26+0.5*e24*e272+e27*e25*e28-0.5*e24*e202-0.5*e24*e222-0.5*e24*e262-0.5*e24*e282; A(4,10)=-e04*e38*e08-e04*e32*e02-e04*e36*e06-0.5*e34*e002-0.5*e34*e022-0.5*e34*e062-0.5*e34*e082+e37*e03*e06+e37*e05*e08-e04*e30*e00+0.5*e34*e032+0.5*e34*e052+0.5*e34*e072+1.5*e34*e042+e01*e30*e03+e01*e00*e33+e01*e31*e04+e01*e32*e05+e01*e02*e35+e31*e00*e03+e31*e02*e05+e04*e33*e03+e04*e35*e05+e07*e03*e36+e07*e04*e37+e07*e35*e08+e07*e05*e38+0.5*e012*e34+e07*e33*e06; A(4,11)=e07*e13*e36+e01*e12*e35-e04*e30*e10+e17*e04*e37+e17*e35*e08+e17*e05*e38+e37*e13*e06+e37*e03*e16+e37*e15*e08+e37*e05*e18-e04*e36*e16+e17*e33*e06+e04*e33*e13+e04*e35*e15+3*e04*e34*e14+e14*e33*e03+e14*e35*e05+e34*e13*e03+e34*e15*e05+e07*e33*e16+e07*e35*e18+e07*e15*e38+e07*e34*e17+e07*e14*e37+e17*e03*e36+e31*e10*e03+e01*e30*e13+e01*e10*e33+e01*e32*e15+e01*e31*e14+e01*e11*e34+e11*e30*e03+e11*e00*e33+e11*e31*e04+e11*e32*e05+e11*e02*e35+e31*e00*e13+e31*e12*e05+e31*e02*e15-e34*e12*e02-e34*e16*e06-e34*e18*e08-e14*e32*e02-e14*e36*e06-e14*e38*e08-e34*e10*e00-e04*e32*e12-e04*e38*e18-e14*e30*e00; A(4,12)=e11*e32*e15-0.5*e34*e102-0.5*e34*e162-0.5*e34*e122-0.5*e34*e182+e37*e13*e16+0.5*e112*e34+1.5*e34*e142+0.5*e34*e132+0.5*e34*e152+0.5*e34*e172+e11*e30*e13+e11*e10*e33+e11*e12*e35+e11*e31*e14+e31*e10*e13+e31*e12*e15+e14*e33*e13+e14*e35*e15+e17*e33*e16+e17*e13*e36+e17*e35*e18+e17*e15*e38+e17*e14*e37+e37*e15*e18-e14*e30*e10-e14*e36*e16-e14*e32*e12-e14*e38*e18; A(4,13)=e01*e22*e35-e04*e30*e20-e04*e32*e22+e01*e31*e24+e01*e21*e34+e01*e32*e25+e21*e30*e03+e21*e00*e33+e21*e31*e04+e21*e32*e05+e21*e02*e35+e31*e20*e03+e31*e00*e23+e31*e22*e05+e31*e02*e25+e04*e33*e23+3*e04*e34*e24+e04*e35*e25+e24*e33*e03+e37*e05*e28-e04*e36*e26-e04*e38*e28-e24*e30*e00-e24*e32*e02-e24*e36*e06-e24*e38*e08+e24*e35*e05+e34*e23*e03+e34*e25*e05+e07*e33*e26+e07*e23*e36+e07*e34*e27+e07*e24*e37+e07*e35*e28+e07*e25*e38+e27*e33*e06+e27*e03*e36+e27*e04*e37+e27*e35*e08+e27*e05*e38+e37*e23*e06+e37*e03*e26+e37*e25*e08-e34*e20*e00-e34*e22*e02-e34*e26*e06-e34*e28*e08+e01*e30*e23+e01*e20*e33; A(4,14)=e21*e10*e33+e11*e30*e23+e11*e20*e33+e11*e31*e24+e11*e21*e34+e11*e32*e25+e11*e22*e35+e21*e30*e13+e21*e32*e15+e21*e12*e35+e21*e31*e14+e31*e20*e13+e31*e10*e23+e31*e22*e15+e31*e12*e25+e14*e33*e23+3*e14*e34*e24+e14*e35*e25+e24*e33*e13+e24*e35*e15+e34*e23*e13+e34*e25*e15+e17*e33*e26+e17*e23*e36+e17*e34*e27+e17*e24*e37+e17*e35*e28+e17*e25*e38+e27*e33*e16+e27*e13*e36+e27*e35*e18+e27*e15*e38+e27*e14*e37+e37*e23*e16+e37*e13*e26+e37*e25*e18+e37*e15*e28-e34*e28*e18-e34*e22*e12-e14*e32*e22-e14*e36*e26-e14*e38*e28-e24*e30*e10-e24*e36*e16-e24*e32*e12-e24*e38*e18-e34*e20*e10-e34*e26*e16-e14*e30*e20; A(4,15)=-0.5*e34*e202-0.5*e34*e222-0.5*e34*e262-0.5*e34*e282+e37*e25*e28-e24*e32*e22-e24*e36*e26-e24*e38*e28-e24*e30*e20+0.5*e212*e34+1.5*e34*e242+0.5*e34*e232+0.5*e34*e252+0.5*e34*e272+e21*e30*e23+e21*e20*e33+e21*e31*e24+e21*e32*e25+e21*e22*e35+e31*e20*e23+e31*e22*e25+e24*e33*e23+e24*e35*e25+e27*e33*e26+e27*e23*e36+e27*e24*e37+e27*e35*e28+e27*e25*e38+e37*e23*e26; A(4,16)=e37*e33*e06+e01*e30*e33+e01*e31*e34+e31*e30*e03+e31*e02*e35+e34*e33*e03+e34*e35*e05+e07*e33*e36+e07*e35*e38+e07*e34*e37+e37*e03*e36+e37*e35*e08+e37*e05*e38-e34*e32*e02-e34*e36*e06-e34*e38*e08+e31*e32*e05+e31*e00*e33+0.5*e312*e04+0.5*e04*e332+0.5*e04*e352+1.5*e04*e342+0.5*e04*e372+e01*e32*e35-0.5*e04*e302-0.5*e04*e322-0.5*e04*e362-0.5*e04*e382-e34*e30*e00; A(4,17)=0.5*e14*e372-0.5*e14*e302-0.5*e14*e322-0.5*e14*e362-0.5*e14*e382+0.5*e312*e14+0.5*e14*e332+0.5*e14*e352+1.5*e14*e342+e11*e30*e33+e11*e32*e35+e11*e31*e34+e31*e30*e13+e31*e10*e33+e31*e32*e15+e31*e12*e35+e34*e33*e13+e34*e35*e15+e17*e33*e36+e17*e35*e38+e17*e34*e37+e37*e33*e16+e37*e13*e36+e37*e35*e18+e37*e15*e38-e34*e30*e10-e34*e36*e16-e34*e32*e12-e34*e38*e18; A(4,18)=-e34*e32*e22-e34*e36*e26-e34*e38*e28+0.5*e24*e332+0.5*e24*e352+1.5*e24*e342+0.5*e24*e372-0.5*e24*e302-0.5*e24*e322-0.5*e24*e362-0.5*e24*e382+e21*e30*e33+0.5*e312*e24+e21*e32*e35+e21*e31*e34+e31*e30*e23+e31*e20*e33+e31*e32*e25+e31*e22*e35+e34*e33*e23+e34*e35*e25+e27*e33*e36+e27*e35*e38+e27*e34*e37+e37*e33*e26+e37*e23*e36+e37*e35*e28+e37*e25*e38-e34*e30*e20; A(4,19)=e31*e30*e33+e31*e32*e35+0.5*e312*e34+0.5*e34*e332+0.5*e34*e352+0.5*e343+e37*e33*e36+e37*e35*e38+0.5*e34*e372-0.5*e34*e302-0.5*e34*e322-0.5*e34*e362-0.5*e34*e382; A(5,0)=e01*e00*e06+0.5*e012*e07+e01*e02*e08+e04*e03*e06+0.5*e042*e07+e04*e05*e08+0.5*e07*e062+0.5*e073+0.5*e07*e082-0.5*e07*e002-0.5*e07*e022-0.5*e07*e032-0.5*e07*e052; A(5,1)=e04*e13*e06+0.5*e042*e17+1.5*e17*e072+0.5*e17*e062+0.5*e17*e082-0.5*e17*e002-0.5*e17*e022-0.5*e17*e032-0.5*e17*e052+e01*e10*e06+e07*e16*e06+e07*e18*e08-e07*e10*e00-e07*e12*e02-e07*e13*e03-e07*e15*e05+e01*e00*e16+e01*e11*e07+e01*e12*e08+e01*e02*e18+e11*e00*e06+e11*e02*e08+e04*e03*e16+e04*e14*e07+e04*e15*e08+e04*e05*e18+e14*e03*e06+e14*e05*e08+0.5*e012*e17; A(5,2)=-e17*e10*e00+0.5*e112*e07+0.5*e142*e07+0.5*e07*e162+0.5*e07*e182+1.5*e07*e172-0.5*e07*e102-0.5*e07*e152-0.5*e07*e132-0.5*e07*e122+e01*e10*e16+e01*e12*e18+e01*e11*e17+e11*e10*e06+e11*e00*e16+e11*e12*e08+e11*e02*e18+e04*e13*e16+e04*e15*e18+e04*e14*e17+e14*e13*e06+e14*e03*e16+e14*e15*e08+e14*e05*e18+e17*e16*e06+e17*e18*e08-e17*e12*e02-e17*e13*e03-e17*e15*e05; A(5,3)=e11*e10*e16+e11*e12*e18+0.5*e112*e17+e14*e13*e16+e14*e15*e18+0.5*e142*e17+0.5*e17*e162+0.5*e17*e182+0.5*e173-0.5*e17*e102-0.5*e17*e152-0.5*e17*e132-0.5*e17*e122; A(5,4)=e01*e22*e08+e07*e28*e08-e07*e20*e00-e07*e23*e03-e07*e22*e02-e07*e25*e05+0.5*e012*e27+0.5*e042*e27+1.5*e27*e072+0.5*e27*e062+0.5*e27*e082-0.5*e27*e002-0.5*e27*e022-0.5*e27*e032-0.5*e27*e052+e07*e26*e06+e01*e20*e06+e01*e00*e26+e01*e21*e07+e01*e02*e28+e21*e00*e06+e21*e02*e08+e04*e23*e06+e04*e03*e26+e04*e24*e07+e04*e25*e08+e04*e05*e28+e24*e03*e06+e24*e05*e08; A(5,5)=e14*e24*e07+e14*e03*e26+e14*e23*e06+e04*e14*e27+e04*e24*e17+e04*e15*e28+e04*e25*e18+e04*e13*e26+e04*e23*e16+e21*e02*e18+e21*e12*e08-e27*e15*e05-e27*e13*e03-e27*e12*e02-e27*e10*e00-e17*e25*e05-e17*e23*e03-e17*e22*e02-e17*e20*e00-e07*e22*e12-e07*e23*e13-e07*e25*e15-e07*e20*e10+e27*e18*e08+e27*e16*e06+e17*e28*e08+e17*e26*e06+3*e07*e27*e17+e07*e28*e18+e07*e26*e16+e24*e05*e18+e24*e15*e08+e24*e03*e16+e24*e13*e06+e14*e05*e28+e14*e25*e08+e01*e12*e28+e01*e20*e16+e01*e10*e26+e01*e22*e18+e01*e21*e17+e11*e20*e06+e01*e11*e27+e21*e00*e16+e21*e10*e06+e11*e21*e07+e11*e22*e08+e11*e02*e28+e11*e00*e26; A(5,6)=-0.5*e27*e102-0.5*e27*e152-0.5*e27*e132-0.5*e27*e122+0.5*e142*e27+1.5*e27*e172+0.5*e27*e162+0.5*e27*e182+0.5*e112*e27+e11*e22*e18+e11*e10*e26+e11*e20*e16-e17*e22*e12-e17*e23*e13-e17*e25*e15-e17*e20*e10+e17*e28*e18+e17*e26*e16+e24*e15*e18+e24*e13*e16+e14*e24*e17+e14*e15*e28+e14*e25*e18+e14*e13*e26+e14*e23*e16+e21*e12*e18+e21*e10*e16+e11*e21*e17+e11*e12*e28; A(5,7)=-0.5*e07*e252+e27*e26*e06+e27*e28*e08-e27*e20*e00-e27*e22*e02-e27*e23*e03-e27*e25*e05+1.5*e07*e272+0.5*e07*e282+e01*e22*e28+e21*e20*e06+e21*e00*e26+e21*e22*e08+e21*e02*e28+e04*e23*e26+e04*e24*e27+e04*e25*e28+e24*e23*e06+e24*e03*e26+e24*e25*e08+e24*e05*e28+0.5*e212*e07+0.5*e242*e07+0.5*e07*e262+e01*e20*e26+e01*e21*e27-0.5*e07*e202-0.5*e07*e232-0.5*e07*e222; A(5,8)=-e27*e25*e15-e27*e23*e13-e27*e22*e12-0.5*e17*e252-0.5*e17*e202-0.5*e17*e222-0.5*e17*e232+0.5*e17*e262+1.5*e17*e272+0.5*e17*e282+e24*e23*e16+e24*e13*e26+e24*e25*e18+e24*e15*e28+e27*e26*e16+e27*e28*e18-e27*e20*e10+e14*e24*e27+e14*e25*e28+0.5*e212*e17+0.5*e242*e17+e11*e20*e26+e11*e21*e27+e11*e22*e28+e21*e20*e16+e21*e10*e26+e21*e22*e18+e21*e12*e28+e14*e23*e26; A(5,9)=e21*e20*e26+0.5*e212*e27+e21*e22*e28+e24*e23*e26+0.5*e242*e27+e24*e25*e28+0.5*e27*e262+0.5*e273+0.5*e27*e282-0.5*e27*e202-0.5*e27*e222-0.5*e27*e232-0.5*e27*e252; A(5,10)=e04*e05*e38+e01*e30*e06-0.5*e37*e002-0.5*e37*e022-0.5*e37*e032-0.5*e37*e052-e07*e32*e02-e07*e35*e05-e07*e33*e03+e07*e36*e06+e07*e38*e08-e07*e30*e00+1.5*e37*e072+0.5*e37*e062+0.5*e37*e082+e01*e02*e38+e31*e00*e06+e31*e02*e08+e04*e33*e06+e04*e03*e36+e04*e34*e07+e04*e35*e08+e34*e03*e06+e34*e05*e08+0.5*e012*e37+0.5*e042*e37+e01*e00*e36+e01*e31*e07+e01*e32*e08; A(5,11)=e14*e33*e06+e11*e30*e06+e11*e00*e36+e11*e31*e07+e31*e10*e06+e11*e32*e08+e11*e02*e38+e31*e00*e16+e31*e12*e08+e31*e02*e18+e04*e33*e16+e04*e13*e36+e04*e35*e18+e04*e15*e38+e01*e10*e36+e01*e32*e18+e01*e12*e38+e01*e31*e17+e01*e11*e37+e01*e30*e16-e17*e35*e05-e37*e10*e00-e37*e12*e02-e37*e13*e03-e37*e15*e05+e37*e18*e08-e07*e30*e10-e07*e35*e15-e07*e33*e13-e07*e32*e12-e17*e30*e00-e17*e32*e02-e17*e33*e03+e07*e38*e18+3*e07*e37*e17+e17*e36*e06+e17*e38*e08+e37*e16*e06+e04*e34*e17+e04*e14*e37+e14*e03*e36+e14*e34*e07+e14*e35*e08+e14*e05*e38+e34*e13*e06+e34*e03*e16+e34*e15*e08+e34*e05*e18+e07*e36*e16; A(5,12)=e11*e32*e18-0.5*e37*e102-0.5*e37*e152-0.5*e37*e132-0.5*e37*e122+0.5*e112*e37+0.5*e142*e37+1.5*e37*e172+0.5*e37*e162+0.5*e37*e182+e11*e10*e36+e11*e12*e38+e11*e31*e17+e31*e10*e16+e31*e12*e18+e14*e33*e16+e14*e13*e36+e14*e35*e18+e14*e15*e38+e14*e34*e17+e34*e13*e16+e34*e15*e18+e17*e36*e16+e17*e38*e18-e17*e30*e10-e17*e35*e15-e17*e33*e13-e17*e32*e12+e11*e30*e16; A(5,13)=e01*e20*e36+e01*e31*e27+e01*e21*e37+e01*e32*e28+e01*e22*e38+e21*e30*e06+e21*e00*e36+e21*e31*e07+e21*e32*e08+e21*e02*e38+e01*e30*e26+e31*e20*e06+e31*e00*e26+e31*e22*e08+e31*e02*e28+e04*e33*e26+e04*e23*e36+e04*e34*e27+e04*e24*e37+e04*e35*e28+e04*e25*e38+e24*e33*e06+e24*e03*e36+e24*e34*e07+e24*e35*e08+e24*e05*e38+e34*e23*e06+e34*e03*e26+e34*e25*e08+e34*e05*e28+e07*e36*e26+3*e07*e37*e27+e07*e38*e28+e27*e36*e06+e27*e38*e08+e37*e26*e06+e37*e28*e08-e07*e30*e20-e07*e32*e22-e07*e33*e23-e07*e35*e25-e27*e30*e00-e27*e32*e02-e27*e33*e03-e27*e35*e05-e37*e20*e00-e37*e22*e02-e37*e23*e03-e37*e25*e05; A(5,14)=e11*e30*e26+e11*e20*e36+e11*e31*e27+e11*e21*e37+e11*e32*e28+e11*e22*e38+e21*e10*e36+e21*e32*e18+e21*e12*e38+e21*e31*e17+e31*e20*e16+e31*e10*e26+e31*e22*e18+e31*e12*e28+e14*e33*e26+e14*e23*e36+e14*e34*e27+e14*e24*e37+e14*e35*e28+e14*e25*e38+e24*e33*e16+e24*e13*e36+e24*e35*e18+e24*e15*e38+e24*e34*e17+e34*e23*e16+e34*e13*e26+e34*e25*e18+e34*e15*e28+e17*e36*e26+3*e17*e37*e27+e17*e38*e28+e27*e36*e16+e27*e38*e18+e37*e26*e16+e37*e28*e18-e17*e30*e20-e17*e32*e22-e17*e33*e23-e17*e35*e25-e27*e30*e10-e27*e35*e15-e27*e33*e13-e27*e32*e12-e37*e20*e10-e37*e25*e15-e37*e23*e13-e37*e22*e12+e21*e30*e16; A(5,15)=e21*e20*e36+e21*e31*e27+e21*e32*e28+e21*e22*e38+e31*e22*e28+e24*e33*e26+e24*e23*e36+e24*e34*e27+e24*e35*e28+e24*e25*e38+e34*e23*e26+e34*e25*e28+e27*e36*e26+e27*e38*e28-e27*e30*e20-e27*e32*e22-e27*e33*e23-e27*e35*e25+0.5*e242*e37+1.5*e37*e272+0.5*e37*e262+0.5*e37*e282+e31*e20*e26+e21*e30*e26+0.5*e212*e37-0.5*e37*e202-0.5*e37*e222-0.5*e37*e232-0.5*e37*e252; A(5,16)=e01*e30*e36+e01*e32*e38+e01*e31*e37+e31*e30*e06+e31*e00*e36+e31*e32*e08+e31*e02*e38+e04*e33*e36+e04*e35*e38+e04*e34*e37+e34*e33*e06+e34*e03*e36+e34*e35*e08+e34*e05*e38+e37*e36*e06+e37*e38*e08-e37*e30*e00-e37*e32*e02-e37*e33*e03-e37*e35*e05+0.5*e312*e07+0.5*e342*e07+0.5*e07*e362+0.5*e07*e382+1.5*e07*e372-0.5*e07*e302-0.5*e07*e352-0.5*e07*e322-0.5*e07*e332; A(5,17)=0.5*e312*e17+0.5*e342*e17+0.5*e17*e362+0.5*e17*e382+1.5*e17*e372-0.5*e17*e302-0.5*e17*e352-0.5*e17*e322-0.5*e17*e332-e37*e32*e12-e37*e33*e13+e11*e30*e36+e11*e32*e38+e11*e31*e37+e31*e30*e16+e31*e10*e36+e31*e32*e18+e31*e12*e38+e14*e33*e36+e14*e35*e38+e14*e34*e37+e34*e33*e16+e34*e13*e36+e34*e35*e18+e34*e15*e38+e37*e36*e16+e37*e38*e18-e37*e30*e10-e37*e35*e15; A(5,18)=e21*e31*e37-0.5*e27*e332+e21*e30*e36+e21*e32*e38+e31*e30*e26+e31*e20*e36+e31*e32*e28+e31*e22*e38+e24*e33*e36+e24*e35*e38+e24*e34*e37+e34*e33*e26+e34*e23*e36+e34*e35*e28+e34*e25*e38+e37*e36*e26+e37*e38*e28-e37*e30*e20-e37*e32*e22-e37*e33*e23-e37*e35*e25+0.5*e312*e27+0.5*e342*e27+0.5*e27*e362+0.5*e27*e382+1.5*e27*e372-0.5*e27*e302-0.5*e27*e352-0.5*e27*e322; A(5,19)=e31*e30*e36+e31*e32*e38+0.5*e312*e37+e34*e33*e36+e34*e35*e38+0.5*e342*e37+0.5*e37*e362+0.5*e37*e382+0.5*e373-0.5*e37*e302-0.5*e37*e352-0.5*e37*e322-0.5*e37*e332; A(6,0)=0.5*e02*e002+0.5*e02*e012+0.5*e023+e05*e00*e03+e05*e01*e04+0.5*e02*e052+e08*e00*e06+e08*e01*e07+0.5*e02*e082-0.5*e02*e032-0.5*e02*e042-0.5*e02*e062-0.5*e02*e072; A(6,1)=-0.5*e12*e042-0.5*e12*e062-0.5*e12*e072+0.5*e12*e082-0.5*e12*e032+1.5*e12*e022+0.5*e12*e002+0.5*e12*e012+0.5*e12*e052+e02*e10*e00+e02*e11*e01+e05*e10*e03+e05*e00*e13+e05*e11*e04+e05*e01*e14+e05*e02*e15+e15*e00*e03+e15*e01*e04+e08*e10*e06+e08*e00*e16+e08*e11*e07+e08*e01*e17+e08*e02*e18+e18*e00*e06+e18*e01*e07-e02*e13*e03-e02*e14*e04-e02*e16*e06-e02*e17*e07; A(6,2)=0.5*e02*e102+1.5*e02*e122+0.5*e02*e112+0.5*e02*e152+0.5*e02*e182-0.5*e02*e162-0.5*e02*e172-0.5*e02*e132-0.5*e02*e142+e12*e10*e00+e12*e11*e01+e05*e10*e13+e05*e12*e15+e05*e11*e14+e15*e10*e03+e15*e00*e13+e15*e11*e04+e15*e01*e14+e08*e10*e16+e08*e12*e18+e08*e11*e17+e18*e10*e06+e18*e00*e16+e18*e11*e07+e18*e01*e17-e12*e13*e03-e12*e14*e04-e12*e16*e06-e12*e17*e07; A(6,3)=0.5*e12*e102+0.5*e123+0.5*e12*e112+e15*e10*e13+0.5*e12*e152+e15*e11*e14+e18*e10*e16+0.5*e12*e182+e18*e11*e17-0.5*e12*e162-0.5*e12*e172-0.5*e12*e132-0.5*e12*e142; A(6,4)=-0.5*e22*e032-0.5*e22*e042-0.5*e22*e062-0.5*e22*e072+0.5*e22*e082+1.5*e22*e022+0.5*e22*e002+0.5*e22*e012+0.5*e22*e052+e02*e20*e00+e02*e21*e01+e05*e20*e03+e05*e00*e23+e05*e21*e04+e05*e01*e24+e05*e02*e25+e25*e00*e03+e25*e01*e04+e08*e20*e06+e08*e00*e26+e08*e21*e07+e08*e01*e27+e08*e02*e28+e28*e00*e06+e28*e01*e07-e02*e27*e07-e02*e23*e03-e02*e24*e04-e02*e26*e06; A(6,5)=-e22*e17*e07-e22*e16*e06-e22*e14*e04-e22*e13*e03-e12*e26*e06-e12*e24*e04-e12*e23*e03-e12*e27*e07-e02*e24*e14-e02*e23*e13-e02*e27*e17-e02*e26*e16+e28*e01*e17+e28*e11*e07+e28*e00*e16+e28*e10*e06+e18*e02*e28+e18*e01*e27+e18*e21*e07+e18*e00*e26+e18*e20*e06+e08*e11*e27+e08*e21*e17+e08*e12*e28+e08*e22*e18+e08*e10*e26+e25*e01*e14+e25*e11*e04+e25*e00*e13+e25*e10*e03+e15*e01*e24+e02*e21*e11+e12*e21*e01+e15*e02*e25+e15*e21*e04+e05*e22*e15+e05*e11*e24+e15*e20*e03+e15*e00*e23+e05*e10*e23+e05*e12*e25+e05*e21*e14+e22*e10*e00+e22*e11*e01+e02*e20*e10+3*e02*e22*e12+e12*e20*e00+e08*e20*e16+e05*e20*e13; A(6,6)=-e12*e24*e14-e12*e23*e13-e12*e27*e17-e12*e26*e16+e28*e11*e17+e28*e10*e16+e18*e11*e27+e18*e21*e17+e18*e12*e28+e18*e10*e26+e18*e20*e16+e25*e11*e14+e25*e10*e13+e15*e11*e24+e15*e21*e14+e15*e12*e25+e15*e10*e23+e15*e20*e13+e12*e21*e11+0.5*e22*e182+0.5*e22*e152+1.5*e22*e122+0.5*e22*e102+e12*e20*e10+0.5*e22*e112-0.5*e22*e172-0.5*e22*e132-0.5*e22*e142-0.5*e22*e162; A(6,7)=0.5*e02*e282+e28*e01*e27-e22*e27*e07-e22*e23*e03-e22*e24*e04-e22*e26*e06+0.5*e02*e252+e05*e20*e23+e05*e22*e25+e25*e20*e03+e25*e00*e23+e25*e21*e04+e25*e01*e24+e08*e20*e26+e08*e21*e27+e08*e22*e28+e28*e20*e06+e28*e00*e26+e28*e21*e07+e05*e21*e24+0.5*e02*e202+0.5*e02*e212+1.5*e02*e222+e22*e20*e00+e22*e21*e01-0.5*e02*e272-0.5*e02*e242-0.5*e02*e232-0.5*e02*e262; A(6,8)=-e22*e27*e17-e22*e23*e13-e22*e24*e14-0.5*e12*e232-0.5*e12*e262-0.5*e12*e242-0.5*e12*e272+0.5*e12*e282+e18*e21*e27+e28*e20*e16+e28*e10*e26+e28*e21*e17+e28*e11*e27-e22*e26*e16+e18*e22*e28+0.5*e12*e252+0.5*e12*e202+0.5*e12*e212+1.5*e12*e222+e22*e20*e10+e15*e20*e23+e15*e21*e24+e15*e22*e25+e25*e20*e13+e25*e10*e23+e25*e21*e14+e25*e11*e24+e18*e20*e26+e22*e21*e11; A(6,9)=0.5*e22*e202+0.5*e22*e212+0.5*e223+e25*e20*e23+e25*e21*e24+0.5*e22*e252+e28*e20*e26+e28*e21*e27+0.5*e22*e282-0.5*e22*e232-0.5*e22*e262-0.5*e22*e242-0.5*e22*e272; A(6,10)=e08*e31*e07-0.5*e32*e032-e02*e33*e03-e02*e34*e04-e02*e36*e06-0.5*e32*e042-0.5*e32*e062-0.5*e32*e072+e38*e01*e07+e38*e00*e06-e02*e37*e07+e05*e31*e04+e05*e01*e34+e05*e02*e35+e35*e01*e04+e35*e00*e03+e08*e30*e06+e08*e00*e36+e08*e01*e37+e08*e02*e38+0.5*e32*e052+e02*e30*e00+e02*e31*e01+e05*e30*e03+e05*e00*e33+1.5*e32*e022+0.5*e32*e012+0.5*e32*e002+0.5*e32*e082; A(6,11)=e05*e32*e15+e32*e11*e01+e38*e10*e06+e08*e12*e38-e32*e14*e04-e32*e16*e06-e32*e17*e07-e12*e36*e06-e32*e13*e03-e02*e34*e14-e12*e37*e07-e12*e33*e03-e12*e34*e04-e02*e37*e17-e02*e33*e13+e38*e01*e17-e02*e36*e16+e18*e01*e37+e18*e02*e38+e38*e00*e16+e38*e11*e07+e08*e30*e16+e08*e10*e36+e08*e32*e18+e08*e31*e17+e08*e11*e37+e18*e30*e06+e18*e00*e36+e18*e31*e07+e35*e10*e03+e35*e00*e13+e35*e11*e04+e35*e01*e14+e15*e02*e35+e05*e10*e33+e05*e12*e35+e05*e31*e14+e05*e11*e34+e15*e30*e03+e15*e00*e33+e15*e31*e04+e15*e01*e34+e05*e30*e13+e02*e30*e10+e02*e31*e11+3*e02*e32*e12+e12*e30*e00+e12*e31*e01+e32*e10*e00; A(6,12)=0.5*e32*e102+0.5*e32*e112+e12*e30*e10+1.5*e32*e122+e12*e31*e11+e15*e30*e13+e15*e10*e33+e15*e12*e35+e15*e31*e14+e15*e11*e34+e35*e10*e13-0.5*e32*e162-0.5*e32*e172-0.5*e32*e132-0.5*e32*e142-e12*e37*e17-e12*e33*e13-e12*e34*e14+0.5*e32*e182+0.5*e32*e152+e35*e11*e14+e18*e30*e16+e18*e10*e36+e18*e12*e38+e18*e31*e17+e18*e11*e37+e38*e10*e16+e38*e11*e17-e12*e36*e16; A(6,13)=3*e02*e32*e22+e05*e31*e24+e08*e22*e38+e02*e31*e21+e22*e30*e00+e22*e31*e01+e32*e20*e00+e32*e21*e01+e05*e30*e23+e05*e20*e33+e05*e21*e34-e22*e37*e07-e22*e33*e03-e22*e34*e04-e22*e36*e06-e32*e27*e07-e32*e23*e03-e32*e24*e04-e32*e26*e06+e05*e32*e25+e25*e30*e03+e25*e00*e33+e25*e31*e04+e25*e01*e34+e25*e02*e35+e35*e20*e03+e35*e00*e23+e35*e21*e04+e35*e01*e24+e08*e30*e26+e08*e20*e36+e08*e31*e27+e08*e21*e37+e08*e32*e28+e28*e30*e06+e28*e00*e36+e28*e31*e07+e28*e01*e37+e28*e02*e38+e38*e20*e06+e38*e00*e26+e38*e21*e07+e38*e01*e27-e02*e33*e23-e02*e36*e26-e02*e34*e24-e02*e37*e27+e05*e22*e35+e02*e30*e20; A(6,14)=e18*e22*e38+e12*e31*e21+3*e12*e32*e22+e22*e30*e10+e22*e31*e11+e32*e20*e10+e32*e21*e11+e15*e30*e23+e15*e20*e33+e15*e31*e24+e15*e21*e34+e15*e32*e25+e15*e22*e35+e25*e30*e13+e25*e10*e33+e25*e12*e35+e25*e31*e14+e25*e11*e34+e35*e20*e13+e35*e10*e23+e35*e21*e14+e35*e11*e24+e18*e30*e26+e18*e20*e36+e18*e31*e27+e18*e21*e37+e18*e32*e28+e28*e30*e16+e28*e10*e36+e28*e12*e38+e28*e31*e17+e28*e11*e37+e38*e20*e16+e38*e10*e26+e12*e30*e20-e22*e37*e17-e22*e33*e13-e22*e34*e14-e32*e26*e16-e32*e27*e17-e32*e23*e13-e32*e24*e14-e22*e36*e16+e38*e21*e17+e38*e11*e27-e12*e33*e23-e12*e36*e26-e12*e34*e24-e12*e37*e27; A(6,15)=e25*e30*e23+e22*e30*e20+e22*e31*e21+e25*e20*e33+e25*e31*e24+e25*e21*e34+e25*e22*e35+e35*e20*e23+e35*e21*e24+e28*e30*e26+e28*e20*e36+e28*e31*e27+e28*e21*e37+e28*e22*e38+e38*e20*e26+e38*e21*e27-e22*e33*e23-e22*e36*e26-e22*e34*e24-e22*e37*e27+0.5*e32*e212+0.5*e32*e252+1.5*e32*e222+0.5*e32*e202+0.5*e32*e282-0.5*e32*e232-0.5*e32*e262-0.5*e32*e242-0.5*e32*e272; A(6,16)=0.5*e02*e302+1.5*e02*e322+0.5*e02*e312+0.5*e02*e352+0.5*e02*e382-0.5*e02*e342-0.5*e02*e362-0.5*e02*e332-0.5*e02*e372+e38*e30*e06+e32*e30*e00+e32*e31*e01+e05*e30*e33+e05*e32*e35+e05*e31*e34+e35*e30*e03+e35*e00*e33+e35*e31*e04+e35*e01*e34+e08*e30*e36+e08*e32*e38+e08*e31*e37+e38*e00*e36+e38*e31*e07+e38*e01*e37-e32*e37*e07-e32*e33*e03-e32*e34*e04-e32*e36*e06; A(6,17)=e32*e30*e10+e32*e31*e11+e15*e30*e33+e15*e32*e35+e15*e31*e34+e35*e30*e13+e35*e10*e33+e35*e31*e14+e35*e11*e34+e18*e30*e36+e18*e32*e38+e18*e31*e37+e38*e30*e16+e38*e10*e36+e38*e31*e17+e38*e11*e37-e32*e36*e16-e32*e37*e17-e32*e33*e13-e32*e34*e14+0.5*e12*e382-0.5*e12*e342-0.5*e12*e362-0.5*e12*e332-0.5*e12*e372+0.5*e12*e352+1.5*e12*e322+0.5*e12*e312+0.5*e12*e302; A(6,18)=0.5*e22*e302+0.5*e22*e312+0.5*e22*e352+0.5*e22*e382-0.5*e22*e342-0.5*e22*e362-0.5*e22*e332-0.5*e22*e372+1.5*e22*e322+e32*e30*e20+e32*e31*e21+e25*e30*e33+e25*e32*e35+e25*e31*e34+e35*e30*e23+e35*e20*e33+e35*e31*e24+e35*e21*e34+e28*e30*e36+e28*e32*e38+e28*e31*e37+e38*e30*e26+e38*e20*e36+e38*e31*e27+e38*e21*e37-e32*e33*e23-e32*e36*e26-e32*e34*e24-e32*e37*e27; A(6,19)=0.5*e32*e302+0.5*e323+0.5*e32*e312+e35*e30*e33+0.5*e32*e352+e35*e31*e34+e38*e30*e36+0.5*e32*e382+e38*e31*e37-0.5*e32*e342-0.5*e32*e362-0.5*e32*e332-0.5*e32*e372; A(7,0)=e02*e01*e04+e02*e00*e03+0.5*e022*e05+0.5*e05*e032+0.5*e05*e042+0.5*e053+e08*e03*e06+e08*e04*e07+0.5*e05*e082-0.5*e05*e002-0.5*e05*e062-0.5*e05*e012-0.5*e05*e072; A(7,1)=e08*e13*e06+e02*e10*e03+e02*e00*e13+e02*e11*e04+e02*e01*e14+e02*e12*e05+e12*e01*e04+e12*e00*e03+e05*e13*e03+e05*e14*e04+e08*e03*e16+e08*e14*e07+e08*e04*e17+e08*e05*e18+e18*e03*e06+e18*e04*e07-e05*e10*e00-e05*e11*e01-e05*e16*e06-e05*e17*e07+0.5*e022*e15+1.5*e15*e052+0.5*e15*e032+0.5*e15*e042+0.5*e15*e082-0.5*e15*e002-0.5*e15*e062-0.5*e15*e012-0.5*e15*e072; A(7,2)=0.5*e122*e05+0.5*e05*e132+1.5*e05*e152+0.5*e05*e142+0.5*e05*e182-0.5*e05*e102-0.5*e05*e162-0.5*e05*e112-0.5*e05*e172+e02*e10*e13+e02*e12*e15+e02*e11*e14+e12*e10*e03+e12*e00*e13+e12*e11*e04+e12*e01*e14+e15*e13*e03+e15*e14*e04+e08*e13*e16+e08*e15*e18+e08*e14*e17+e18*e13*e06+e18*e03*e16+e18*e14*e07+e18*e04*e17-e15*e11*e01-e15*e16*e06-e15*e17*e07-e15*e10*e00; A(7,3)=e12*e10*e13+0.5*e122*e15+e12*e11*e14+0.5*e15*e132+0.5*e153+0.5*e15*e142+e18*e13*e16+0.5*e15*e182+e18*e14*e17-0.5*e15*e102-0.5*e15*e162-0.5*e15*e112-0.5*e15*e172; A(7,4)=0.5*e25*e082-0.5*e25*e002-0.5*e25*e062-0.5*e25*e012-0.5*e25*e072+e02*e20*e03+e02*e00*e23+e02*e21*e04+e02*e01*e24+e02*e22*e05+e22*e01*e04+e22*e00*e03+e05*e23*e03+e05*e24*e04+e08*e23*e06+e08*e03*e26+e08*e24*e07+e08*e04*e27+e08*e05*e28+e28*e03*e06+e28*e04*e07-e05*e20*e00-e05*e27*e07-e05*e21*e01-e05*e26*e06+0.5*e022*e25+1.5*e25*e052+0.5*e25*e032+0.5*e25*e042; A(7,5)=-e25*e17*e07-e25*e16*e06-e25*e11*e01-e25*e10*e00-e15*e26*e06-e15*e21*e01-e15*e27*e07-e15*e20*e00-e05*e27*e17-e05*e21*e11-e05*e26*e16-e05*e20*e10+e28*e04*e17+e28*e14*e07+e28*e03*e16+e28*e13*e06+e18*e05*e28+e18*e04*e27+e18*e24*e07+e18*e03*e26+e18*e23*e06+e08*e14*e27+e08*e24*e17+e08*e15*e28+e08*e25*e18+e08*e13*e26+e08*e23*e16+e25*e14*e04+e25*e13*e03+e15*e24*e04+e15*e23*e03+e05*e24*e14+3*e05*e25*e15+e05*e23*e13+e22*e01*e14+e22*e11*e04+e22*e00*e13+e22*e10*e03+e12*e22*e05+e12*e01*e24+e12*e21*e04+e12*e00*e23+e12*e20*e03+e02*e11*e24+e02*e21*e14+e02*e12*e25+e02*e22*e15+e02*e10*e23+e02*e20*e13; A(7,6)=-e15*e27*e17-e15*e21*e11-e15*e26*e16+e28*e14*e17+e28*e13*e16+e18*e14*e27+e18*e24*e17+e18*e15*e28+e18*e13*e26+e15*e24*e14+e15*e23*e13+e22*e11*e14+e22*e10*e13+e12*e11*e24+e12*e21*e14+e12*e22*e15+e12*e10*e23+e18*e23*e16+0.5*e25*e142+0.5*e25*e182+1.5*e25*e152+0.5*e25*e132+0.5*e122*e25+e12*e20*e13-0.5*e25*e172-0.5*e25*e162-0.5*e25*e112-0.5*e25*e102-e15*e20*e10; A(7,7)=e28*e24*e07-0.5*e05*e272-0.5*e05*e262-0.5*e05*e212+0.5*e05*e282-0.5*e05*e202+e28*e23*e06+e08*e23*e26+e08*e25*e28+e08*e24*e27+e28*e03*e26+e28*e04*e27-e25*e27*e07-e25*e21*e01-e25*e26*e06+e02*e20*e23+e02*e22*e25+e02*e21*e24+e22*e20*e03+e22*e00*e23+e22*e21*e04+e22*e01*e24+e25*e23*e03+e25*e24*e04+0.5*e222*e05+0.5*e05*e232+1.5*e05*e252+0.5*e05*e242-e25*e20*e00; A(7,8)=-0.5*e15*e202-0.5*e15*e262-0.5*e15*e212-0.5*e15*e272+e18*e23*e26+e18*e25*e28+e18*e24*e27+e28*e23*e16+e28*e13*e26+e28*e24*e17+e28*e14*e27-e25*e20*e10-e25*e26*e16-e25*e21*e11-e25*e27*e17+0.5*e15*e282+0.5*e15*e232+1.5*e15*e252+0.5*e15*e242+0.5*e222*e15+e12*e21*e24+e22*e20*e13+e22*e10*e23+e22*e21*e14+e22*e11*e24+e25*e23*e13+e25*e24*e14+e12*e20*e23+e12*e22*e25; A(7,9)=e22*e20*e23+0.5*e222*e25+e22*e21*e24+0.5*e25*e232+0.5*e253+0.5*e25*e242+e28*e23*e26+0.5*e25*e282+e28*e24*e27-0.5*e25*e202-0.5*e25*e262-0.5*e25*e212-0.5*e25*e272; A(7,10)=-0.5*e35*e062-0.5*e35*e012-0.5*e35*e072-e05*e30*e00-e05*e31*e01-e05*e36*e06-e05*e37*e07-0.5*e35*e002+0.5*e35*e082+e05*e34*e04+e08*e33*e06+e08*e03*e36+e08*e34*e07+e08*e04*e37+e08*e05*e38+e38*e04*e07+e38*e03*e06+0.5*e022*e35+1.5*e35*e052+0.5*e35*e042+0.5*e35*e032+e02*e30*e03+e02*e00*e33+e02*e31*e04+e02*e01*e34+e02*e32*e05+e32*e01*e04+e32*e00*e03+e05*e33*e03; A(7,11)=e08*e33*e16-e35*e16*e06-e35*e17*e07-e15*e30*e00-e15*e37*e07-e15*e31*e01-e15*e36*e06-e35*e10*e00-e35*e11*e01-e05*e37*e17-e05*e31*e11+e38*e04*e17-e05*e30*e10-e05*e36*e16+e18*e33*e06+e18*e03*e36+e18*e34*e07+e18*e04*e37+e18*e05*e38+e38*e13*e06+e38*e03*e16+e38*e14*e07+e35*e14*e04+e08*e13*e36+e08*e35*e18+e08*e15*e38+e08*e34*e17+e08*e14*e37+e35*e13*e03+e05*e33*e13+3*e05*e35*e15+e05*e34*e14+e15*e33*e03+e15*e34*e04+e12*e01*e34+e12*e32*e05+e32*e10*e03+e32*e00*e13+e32*e11*e04+e32*e01*e14+e12*e30*e03+e02*e30*e13+e02*e32*e15+e02*e10*e33+e02*e12*e35+e12*e00*e33+e02*e31*e14+e02*e11*e34+e12*e31*e04; A(7,12)=-0.5*e35*e162-0.5*e35*e172-e15*e36*e16-e15*e31*e11-e15*e37*e17-0.5*e35*e102-0.5*e35*e112-e15*e30*e10+e18*e13*e36+e18*e15*e38+e18*e34*e17+e18*e14*e37+e38*e13*e16+e38*e14*e17+e18*e33*e16+1.5*e35*e152+0.5*e35*e132+0.5*e35*e142+0.5*e35*e182+0.5*e122*e35+e32*e10*e13+e32*e11*e14+e15*e33*e13+e15*e34*e14+e12*e10*e33+e12*e32*e15+e12*e31*e14+e12*e11*e34+e12*e30*e13; A(7,13)=e05*e33*e23+3*e05*e35*e25+e05*e34*e24+e25*e33*e03+e25*e34*e04+e35*e23*e03+e35*e24*e04+e08*e33*e26+e08*e23*e36+e08*e35*e28+e02*e20*e33+e02*e32*e25+e02*e22*e35+e02*e31*e24+e02*e21*e34+e22*e30*e03+e22*e00*e33+e22*e31*e04+e22*e01*e34+e22*e32*e05+e32*e20*e03+e32*e00*e23+e32*e21*e04+e32*e01*e24+e02*e30*e23-e35*e27*e07-e35*e21*e01-e35*e26*e06+e08*e25*e38+e08*e34*e27+e08*e24*e37+e28*e33*e06+e28*e03*e36+e28*e34*e07+e28*e04*e37+e28*e05*e38+e38*e23*e06+e38*e03*e26+e38*e24*e07+e38*e04*e27-e05*e30*e20-e05*e36*e26-e05*e31*e21-e05*e37*e27-e25*e30*e00-e25*e37*e07-e25*e31*e01-e25*e36*e06-e35*e20*e00; A(7,14)=e12*e21*e34+e18*e25*e38+e12*e30*e23+e12*e20*e33+e12*e32*e25+e12*e22*e35+e12*e31*e24+e22*e30*e13+e22*e10*e33+e22*e32*e15+e22*e31*e14+e22*e11*e34+e32*e20*e13+e32*e10*e23+e32*e21*e14-e25*e30*e10-e25*e36*e16-e25*e31*e11-e25*e37*e17-e35*e20*e10-e35*e26*e16-e35*e21*e11-e35*e27*e17+e15*e33*e23+3*e15*e35*e25+e15*e34*e24+e25*e33*e13+e25*e34*e14+e35*e23*e13+e35*e24*e14+e18*e33*e26+e18*e23*e36+e18*e35*e28+e18*e34*e27+e18*e24*e37+e28*e33*e16+e28*e13*e36+e28*e15*e38+e28*e34*e17+e28*e14*e37+e38*e23*e16+e38*e13*e26+e38*e24*e17+e38*e14*e27-e15*e30*e20-e15*e36*e26-e15*e31*e21-e15*e37*e27+e32*e11*e24; A(7,15)=-0.5*e35*e202-0.5*e35*e262-0.5*e35*e212-0.5*e35*e272+e25*e34*e24+e28*e23*e36+e28*e25*e38+e28*e34*e27+e28*e24*e37+e38*e23*e26+e38*e24*e27-e25*e30*e20-e25*e36*e26-e25*e31*e21-e25*e37*e27+e25*e33*e23+0.5*e222*e35+1.5*e35*e252+0.5*e35*e232+0.5*e35*e242+0.5*e35*e282+e22*e30*e23+e22*e20*e33+e22*e32*e25+e22*e31*e24+e22*e21*e34+e32*e20*e23+e32*e21*e24+e28*e33*e26; A(7,16)=-e35*e30*e00-e35*e31*e01-e35*e36*e06-e35*e37*e07+0.5*e322*e05+0.5*e05*e332+0.5*e05*e342+1.5*e05*e352+0.5*e05*e382-0.5*e05*e302-0.5*e05*e362-0.5*e05*e312-0.5*e05*e372+e02*e30*e33+e02*e31*e34+e02*e32*e35+e32*e30*e03+e32*e00*e33+e32*e31*e04+e32*e01*e34+e35*e33*e03+e35*e34*e04+e08*e33*e36+e08*e34*e37+e08*e35*e38+e38*e33*e06+e38*e03*e36+e38*e34*e07+e38*e04*e37; A(7,17)=-e35*e30*e10+e12*e32*e35-0.5*e15*e362-0.5*e15*e312-0.5*e15*e372-e35*e36*e16+0.5*e322*e15+0.5*e15*e332+0.5*e15*e342+1.5*e15*e352+0.5*e15*e382-0.5*e15*e302+e12*e30*e33+e12*e31*e34+e32*e30*e13+e32*e10*e33+e32*e31*e14+e32*e11*e34+e35*e33*e13+e35*e34*e14+e18*e33*e36+e18*e34*e37+e18*e35*e38+e38*e33*e16+e38*e13*e36+e38*e34*e17+e38*e14*e37-e35*e31*e11-e35*e37*e17; A(7,18)=-0.5*e25*e302-0.5*e25*e362-0.5*e25*e312-0.5*e25*e372+0.5*e322*e25+0.5*e25*e332+0.5*e25*e342+1.5*e25*e352+0.5*e25*e382+e22*e30*e33+e22*e31*e34+e22*e32*e35+e32*e30*e23+e32*e20*e33+e32*e31*e24+e32*e21*e34+e35*e33*e23+e35*e34*e24+e28*e33*e36+e28*e34*e37+e28*e35*e38+e38*e33*e26+e38*e23*e36+e38*e34*e27+e38*e24*e37-e35*e30*e20-e35*e36*e26-e35*e31*e21-e35*e37*e27; A(7,19)=e32*e30*e33+e32*e31*e34+0.5*e322*e35+0.5*e35*e332+0.5*e35*e342+0.5*e353+e38*e33*e36+e38*e34*e37+0.5*e35*e382-0.5*e35*e302-0.5*e35*e362-0.5*e35*e312-0.5*e35*e372; A(8,0)=e02*e00*e06+e02*e01*e07+0.5*e022*e08+e05*e04*e07+e05*e03*e06+0.5*e052*e08+0.5*e08*e062+0.5*e08*e072+0.5*e083-0.5*e08*e042-0.5*e08*e002-0.5*e08*e012-0.5*e08*e032; A(8,1)=e02*e10*e06+e02*e00*e16+e02*e11*e07+e02*e01*e17+e02*e12*e08+e12*e00*e06+e12*e01*e07+e05*e13*e06+e05*e03*e16+e05*e14*e07+e05*e04*e17+e05*e15*e08+e15*e04*e07+e15*e03*e06+e08*e16*e06+e08*e17*e07-e08*e10*e00-e08*e11*e01-e08*e13*e03-e08*e14*e04+0.5*e022*e18+0.5*e052*e18+1.5*e18*e082+0.5*e18*e062+0.5*e18*e072-0.5*e18*e042-0.5*e18*e002-0.5*e18*e012-0.5*e18*e032; A(8,2)=e12*e01*e17+0.5*e152*e08+0.5*e08*e162+1.5*e08*e182+0.5*e08*e172-0.5*e08*e102-0.5*e08*e112-0.5*e08*e132-0.5*e08*e142+e05*e13*e16+e05*e14*e17+e05*e15*e18+e15*e13*e06+e15*e03*e16+e15*e14*e07+e15*e04*e17+e18*e16*e06+e18*e17*e07-e18*e10*e00-e18*e11*e01-e18*e13*e03-e18*e14*e04+0.5*e122*e08+e02*e10*e16+e02*e12*e18+e02*e11*e17+e12*e10*e06+e12*e00*e16+e12*e11*e07; A(8,3)=e12*e10*e16+0.5*e122*e18+e12*e11*e17+e15*e13*e16+e15*e14*e17+0.5*e152*e18+0.5*e18*e162+0.5*e183+0.5*e18*e172-0.5*e18*e102-0.5*e18*e112-0.5*e18*e132-0.5*e18*e142; A(8,4)=-e08*e20*e00+e08*e27*e07-e08*e21*e01-e08*e23*e03-e08*e24*e04+e02*e20*e06+e02*e00*e26+e02*e21*e07+e02*e01*e27+e02*e22*e08+e22*e00*e06+e22*e01*e07+e05*e23*e06+e05*e03*e26+e05*e24*e07+e05*e04*e27+e05*e25*e08+e25*e04*e07+e25*e03*e06+e08*e26*e06+0.5*e022*e28+0.5*e052*e28+1.5*e28*e082+0.5*e28*e062+0.5*e28*e072-0.5*e28*e042-0.5*e28*e002-0.5*e28*e012-0.5*e28*e032; A(8,5)=e22*e10*e06+e22*e11*e07+e22*e01*e17+e05*e23*e16+e05*e13*e26+e05*e25*e18+e05*e15*e28+e05*e24*e17+e05*e14*e27+e15*e23*e06+e15*e03*e26+e15*e24*e07+e15*e04*e27+e15*e25*e08+e25*e13*e06+e25*e03*e16+e25*e14*e07+e25*e04*e17+e08*e26*e16+3*e08*e28*e18+e08*e27*e17+e18*e26*e06+e18*e27*e07+e22*e00*e16+e28*e16*e06+e28*e17*e07-e08*e20*e10-e08*e21*e11-e08*e23*e13-e08*e24*e14-e18*e20*e00-e18*e21*e01-e18*e23*e03-e18*e24*e04-e28*e10*e00-e28*e11*e01-e28*e13*e03-e28*e14*e04+e02*e20*e16+e02*e10*e26+e02*e22*e18+e02*e12*e28+e02*e21*e17+e02*e11*e27+e12*e20*e06+e12*e00*e26+e12*e21*e07+e12*e01*e27+e12*e22*e08; A(8,6)=-e18*e24*e14-e18*e21*e11-e18*e23*e13-e18*e20*e10+e18*e27*e17+e18*e26*e16+e25*e14*e17+e25*e13*e16+e15*e25*e18+e15*e14*e27+e15*e24*e17+e15*e13*e26+e15*e23*e16+e22*e11*e17+e22*e10*e16+e12*e11*e27+e12*e21*e17+e12*e22*e18+e12*e10*e26+e12*e20*e16+0.5*e28*e162+0.5*e28*e172+1.5*e28*e182+0.5*e152*e28-0.5*e28*e142-0.5*e28*e112-0.5*e28*e132-0.5*e28*e102+0.5*e122*e28; A(8,7)=-e28*e24*e04-e28*e21*e01-e28*e23*e03-e28*e20*e00+e28*e27*e07+e28*e26*e06+e25*e04*e27+e25*e24*e07+e25*e03*e26+e05*e24*e27+e05*e25*e28+e05*e23*e26+e22*e01*e27+e22*e21*e07+e22*e00*e26+e22*e20*e06+e02*e22*e28+e02*e20*e26+e02*e21*e27+0.5*e222*e08-0.5*e08*e242-0.5*e08*e212-0.5*e08*e232-0.5*e08*e202+0.5*e08*e262+0.5*e08*e272+1.5*e08*e282+0.5*e252*e08+e25*e23*e06; A(8,8)=e25*e24*e17+e25*e14*e27+e28*e26*e16+e28*e27*e17-e28*e21*e11-e28*e24*e14+e12*e22*e28+e22*e10*e26+e22*e21*e17+e22*e11*e27+e15*e23*e26+e15*e25*e28+e15*e24*e27+e25*e23*e16+e25*e13*e26+e22*e20*e16+0.5*e222*e18+0.5*e252*e18+0.5*e18*e262+0.5*e18*e272+e12*e20*e26+e12*e21*e27-e28*e20*e10-0.5*e18*e232-0.5*e18*e242-e28*e23*e13-0.5*e18*e212+1.5*e18*e282-0.5*e18*e202; A(8,9)=e22*e20*e26+e22*e21*e27+0.5*e222*e28+e25*e23*e26+0.5*e252*e28+e25*e24*e27+0.5*e28*e262+0.5*e28*e272+0.5*e283-0.5*e28*e202-0.5*e28*e212-0.5*e28*e232-0.5*e28*e242; A(8,10)=-e08*e30*e00-0.5*e38*e042-0.5*e38*e002-0.5*e38*e012-0.5*e38*e032+1.5*e38*e082+0.5*e38*e062+0.5*e38*e072+e32*e01*e07+e05*e33*e06+e05*e03*e36+e05*e34*e07+e05*e04*e37+e05*e35*e08+e35*e04*e07+e35*e03*e06+e08*e36*e06+e08*e37*e07+0.5*e052*e38+e32*e00*e06+e02*e30*e06+e02*e00*e36+e02*e31*e07+e02*e01*e37+e02*e32*e08+0.5*e022*e38-e08*e33*e03-e08*e31*e01-e08*e34*e04; A(8,11)=-e38*e11*e01-e38*e14*e04-e38*e10*e00-e38*e13*e03-e18*e30*e00-e18*e33*e03-e18*e31*e01-e18*e34*e04-e08*e30*e10-e08*e33*e13-e08*e31*e11-e08*e34*e14+3*e08*e38*e18+e08*e37*e17+e18*e36*e06+e18*e37*e07+e38*e16*e06+e38*e17*e07+e15*e35*e08+e35*e13*e06+e35*e03*e16+e35*e14*e07+e35*e04*e17+e08*e36*e16+e05*e35*e18+e05*e15*e38+e15*e33*e06+e15*e03*e36+e15*e34*e07+e15*e04*e37+e05*e14*e37+e12*e30*e06+e12*e31*e07+e12*e01*e37+e12*e00*e36+e12*e32*e08+e32*e10*e06+e32*e00*e16+e32*e11*e07+e32*e01*e17+e05*e33*e16+e05*e13*e36+e05*e34*e17+e02*e30*e16+e02*e10*e36+e02*e32*e18+e02*e12*e38+e02*e31*e17+e02*e11*e37; A(8,12)=e12*e30*e16+e12*e10*e36+e12*e32*e18+e12*e31*e17+e12*e11*e37+e32*e10*e16+e32*e11*e17+e15*e33*e16+e15*e13*e36-0.5*e38*e102-0.5*e38*e112-0.5*e38*e132-0.5*e38*e142+0.5*e38*e162+0.5*e38*e172+e15*e34*e17+e15*e14*e37+e15*e35*e18+e35*e13*e16+e35*e14*e17+e18*e36*e16+e18*e37*e17-e18*e30*e10-e18*e33*e13-e18*e31*e11-e18*e34*e14+0.5*e122*e38+0.5*e152*e38+1.5*e38*e182; A(8,13)=e22*e30*e06-e28*e34*e04+e05*e35*e28+e02*e22*e38+e22*e00*e36+e22*e31*e07+e22*e01*e37+e02*e32*e28+e02*e21*e37-e38*e20*e00-e28*e31*e01-e38*e23*e03-e38*e21*e01-e38*e24*e04-e28*e30*e00-e08*e30*e20-e08*e31*e21-e08*e33*e23-e08*e34*e24-e28*e33*e03+e35*e24*e07+e35*e04*e27+e08*e36*e26+e08*e37*e27+3*e08*e38*e28+e28*e36*e06+e28*e37*e07+e38*e26*e06+e38*e27*e07+e25*e04*e37+e25*e35*e08+e35*e23*e06+e35*e03*e26+e05*e23*e36+e05*e25*e38+e05*e34*e27+e05*e24*e37+e25*e33*e06+e25*e03*e36+e25*e34*e07+e05*e33*e26+e32*e21*e07+e32*e01*e27+e22*e32*e08+e32*e20*e06+e32*e00*e26+e02*e30*e26+e02*e20*e36+e02*e31*e27; A(8,14)=e35*e13*e26-e38*e21*e11-e38*e24*e14+e35*e24*e17+e35*e14*e27+e18*e36*e26+e18*e37*e27+3*e18*e38*e28+e28*e36*e16+e28*e37*e17+e38*e26*e16+e38*e27*e17-e18*e30*e20-e18*e31*e21-e18*e33*e23-e18*e34*e24-e28*e30*e10-e28*e33*e13-e28*e31*e11-e28*e34*e14-e38*e20*e10-e38*e23*e13+e35*e23*e16+e12*e20*e36+e12*e30*e26+e12*e31*e27+e12*e21*e37+e12*e32*e28+e12*e22*e38+e22*e30*e16+e22*e10*e36+e22*e32*e18+e22*e31*e17+e22*e11*e37+e32*e20*e16+e32*e10*e26+e32*e21*e17+e32*e11*e27+e15*e33*e26+e15*e23*e36+e15*e35*e28+e15*e25*e38+e15*e34*e27+e15*e24*e37+e25*e33*e16+e25*e13*e36+e25*e34*e17+e25*e14*e37+e25*e35*e18; A(8,15)=-e28*e30*e20+e22*e30*e26+e22*e20*e36+e22*e31*e27+e22*e21*e37+e22*e32*e28+e32*e20*e26+e32*e21*e27+e25*e33*e26+e25*e23*e36+e25*e35*e28+e25*e34*e27+e25*e24*e37+e35*e23*e26+e35*e24*e27+e28*e36*e26+e28*e37*e27-e28*e31*e21-e28*e33*e23-e28*e34*e24-0.5*e38*e242+0.5*e252*e38+1.5*e38*e282+0.5*e38*e262+0.5*e38*e272-0.5*e38*e202-0.5*e38*e212-0.5*e38*e232+0.5*e222*e38; A(8,16)=-0.5*e08*e312-0.5*e08*e342+0.5*e352*e08+0.5*e08*e362+1.5*e08*e382+0.5*e08*e372-0.5*e08*e302-0.5*e08*e332+e02*e30*e36+e02*e32*e38+e02*e31*e37+e32*e30*e06+e32*e00*e36+e32*e31*e07+e32*e01*e37+e05*e33*e36+e05*e34*e37+e05*e35*e38+e35*e33*e06+e35*e03*e36+e35*e34*e07+e35*e04*e37+0.5*e322*e08+e38*e36*e06+e38*e37*e07-e38*e30*e00-e38*e33*e03-e38*e31*e01-e38*e34*e04; A(8,17)=-e38*e30*e10+e38*e36*e16+e38*e37*e17-e38*e33*e13-e38*e31*e11-e38*e34*e14+0.5*e18*e362+e12*e30*e36+e12*e32*e38+e12*e31*e37+e32*e30*e16+e32*e10*e36+e32*e31*e17+e32*e11*e37+e15*e33*e36+e15*e34*e37+e15*e35*e38+e35*e33*e16+e35*e13*e36+e35*e34*e17+e35*e14*e37+0.5*e322*e18+0.5*e352*e18+1.5*e18*e382+0.5*e18*e372-0.5*e18*e302-0.5*e18*e332-0.5*e18*e312-0.5*e18*e342; A(8,18)=-e38*e30*e20+e25*e35*e38+e22*e30*e36+e22*e32*e38+e22*e31*e37+e32*e30*e26+e32*e20*e36+e32*e31*e27+e32*e21*e37+e25*e33*e36+e25*e34*e37+e35*e33*e26+e35*e23*e36+e35*e34*e27+e35*e24*e37+e38*e36*e26+e38*e37*e27-e38*e31*e21-e38*e33*e23-e38*e34*e24-0.5*e28*e332-0.5*e28*e312-0.5*e28*e342+0.5*e322*e28+0.5*e352*e28+0.5*e28*e362+1.5*e28*e382+0.5*e28*e372-0.5*e28*e302; A(8,19)=e32*e30*e36+0.5*e322*e38+e32*e31*e37+e35*e33*e36+e35*e34*e37+0.5*e352*e38+0.5*e38*e362+0.5*e383+0.5*e38*e372-0.5*e38*e302-0.5*e38*e332-0.5*e38*e312-0.5*e38*e342; A(9,0)=e00*e04*e08-e00*e05*e07+e03*e02*e07-e03*e01*e08-e06*e02*e04+e06*e01*e05; A(9,1)=e06*e01*e15-e16*e02*e04+e16*e01*e05+e03*e02*e17-e13*e01*e08+e06*e11*e05+e13*e02*e07+e00*e04*e18+e00*e14*e08-e00*e05*e17-e10*e05*e07-e00*e15*e07-e06*e12*e04-e06*e02*e14-e03*e01*e18-e03*e11*e08+e10*e04*e08+e03*e12*e07; A(9,2)=-e13*e01*e18-e13*e11*e08+e13*e12*e07+e13*e02*e17+e03*e12*e17-e10*e15*e07+e10*e04*e18+e10*e14*e08-e10*e05*e17-e00*e15*e17+e00*e14*e18+e16*e01*e15+e06*e11*e15-e06*e12*e14-e16*e12*e04-e16*e02*e14+e16*e11*e05-e03*e11*e18; A(9,3)=e10*e14*e18-e10*e15*e17-e13*e11*e18+e13*e12*e17+e16*e11*e15-e16*e12*e14; A(9,4)=-e20*e05*e07+e03*e22*e07+e06*e21*e05+e06*e01*e25-e23*e01*e08+e23*e02*e07+e00*e24*e08-e00*e25*e07-e00*e05*e27+e00*e04*e28-e06*e22*e04-e06*e02*e24-e03*e21*e08-e03*e01*e28-e26*e02*e04+e26*e01*e05+e03*e02*e27+e20*e04*e08; A(9,5)=e23*e12*e07-e26*e02*e14+e16*e21*e05-e23*e11*e08+e10*e24*e08-e20*e05*e17+e26*e11*e05+e26*e01*e15+e10*e04*e28+e00*e24*e18-e00*e15*e27+e03*e22*e17-e13*e01*e28+e23*e02*e17+e16*e01*e25+e20*e04*e18+e06*e11*e25+e13*e02*e27-e23*e01*e18-e20*e15*e07-e10*e25*e07+e13*e22*e07-e06*e22*e14-e26*e12*e04-e03*e11*e28-e03*e21*e18-e16*e22*e04-e16*e02*e24-e06*e12*e24+e06*e21*e15+e00*e14*e28-e00*e25*e17+e20*e14*e08-e13*e21*e08-e10*e05*e27+e03*e12*e27; A(9,6)=-e13*e11*e28+e13*e12*e27+e13*e22*e17+e16*e11*e25+e10*e14*e28-e13*e21*e18-e23*e11*e18+e23*e12*e17+e20*e14*e18-e20*e15*e17+e26*e11*e15-e10*e15*e27-e10*e25*e17-e16*e22*e14-e16*e12*e24+e16*e21*e15-e26*e12*e14+e10*e24*e18; A(9,7)=e26*e21*e05+e26*e01*e25+e20*e04*e28+e20*e24*e08-e20*e25*e07+e23*e22*e07+e03*e22*e27-e03*e21*e28-e26*e22*e04-e20*e05*e27-e00*e25*e27+e06*e21*e25-e06*e22*e24+e00*e24*e28-e26*e02*e24-e23*e21*e08-e23*e01*e28+e23*e02*e27; A(9,8)=-e10*e25*e27+e10*e24*e28-e20*e15*e27-e20*e25*e17+e20*e14*e28+e20*e24*e18+e26*e11*e25+e23*e22*e17-e23*e11*e28+e23*e12*e27-e23*e21*e18-e13*e21*e28+e13*e22*e27-e26*e12*e24+e26*e21*e15-e16*e22*e24+e16*e21*e25-e26*e22*e14; A(9,9)=-e20*e25*e27+e20*e24*e28-e23*e21*e28+e23*e22*e27-e26*e22*e24+e26*e21*e25; A(9,10)=e03*e02*e37-e03*e31*e08-e03*e01*e38+e03*e32*e07-e00*e35*e07+e30*e04*e08+e06*e31*e05-e36*e02*e04+e36*e01*e05-e06*e32*e04-e06*e02*e34+e06*e01*e35+e00*e04*e38-e00*e05*e37+e33*e02*e07-e33*e01*e08-e30*e05*e07+e00*e34*e08; A(9,11)=-e36*e12*e04+e30*e04*e18-e30*e15*e07-e36*e02*e14-e30*e05*e17+e30*e14*e08-e00*e35*e17-e00*e15*e37+e33*e02*e17-e06*e32*e14-e06*e12*e34-e16*e32*e04+e06*e31*e15+e06*e11*e35+e00*e34*e18-e10*e35*e07-e33*e11*e08-e33*e01*e18+e16*e01*e35-e16*e02*e34+e16*e31*e05-e03*e31*e18-e03*e11*e38+e03*e32*e17+e13*e02*e37-e13*e31*e08-e13*e01*e38+e10*e34*e08+e00*e14*e38+e36*e11*e05+e36*e01*e15+e03*e12*e37-e10*e05*e37+e10*e04*e38+e33*e12*e07+e13*e32*e07; A(9,12)=-e36*e12*e14-e30*e15*e17+e13*e32*e17-e13*e31*e18-e33*e11*e18+e33*e12*e17+e10*e14*e38+e30*e14*e18-e13*e11*e38+e13*e12*e37-e10*e35*e17+e10*e34*e18-e16*e12*e34-e16*e32*e14+e16*e11*e35+e16*e31*e15+e36*e11*e15-e10*e15*e37; A(9,13)=-e06*e22*e34-e06*e32*e24-e00*e25*e37-e00*e35*e27+e23*e02*e37+e00*e24*e38-e23*e01*e38-e03*e31*e28-e33*e01*e28+e03*e22*e37+e03*e32*e27+e33*e02*e27-e03*e21*e38-e26*e32*e04-e33*e21*e08+e36*e01*e25+e36*e21*e05-e20*e05*e37+e20*e04*e38+e30*e04*e28-e20*e35*e07+e33*e22*e07+e30*e24*e08-e30*e25*e07-e23*e31*e08+e23*e32*e07+e00*e34*e28+e06*e21*e35+e06*e31*e25-e36*e02*e24+e26*e01*e35-e36*e22*e04+e26*e31*e05-e26*e02*e34+e20*e34*e08-e30*e05*e27; A(9,14)=e33*e22*e17+e33*e12*e27+e16*e21*e35-e16*e22*e34-e16*e32*e24+e23*e32*e17-e23*e11*e38-e23*e31*e18+e23*e12*e37-e13*e21*e38-e13*e31*e28+e13*e22*e37+e36*e21*e15-e36*e12*e24+e36*e11*e25-e26*e12*e34-e20*e35*e17+e20*e14*e38+e20*e34*e18+e30*e24*e18-e30*e15*e27-e30*e25*e17+e30*e14*e28-e33*e21*e18+e10*e34*e28+e10*e24*e38-e10*e35*e27-e10*e25*e37-e20*e15*e37-e26*e32*e14+e26*e11*e35+e26*e31*e15-e36*e22*e14+e13*e32*e27+e16*e31*e25-e33*e11*e28; A(9,15)=-e20*e35*e27-e20*e25*e37+e20*e34*e28+e20*e24*e38+e30*e24*e28-e30*e25*e27+e23*e32*e27+e23*e22*e37-e23*e31*e28-e23*e21*e38+e33*e22*e27-e26*e22*e34-e26*e32*e24+e26*e21*e35+e26*e31*e25-e36*e22*e24+e36*e21*e25-e33*e21*e28; A(9,16)=-e33*e01*e38-e03*e31*e38+e00*e34*e38+e33*e32*e07+e03*e32*e37+e06*e31*e35-e00*e35*e37-e36*e32*e04-e06*e32*e34-e36*e02*e34+e36*e01*e35+e36*e31*e05+e30*e04*e38+e30*e34*e08-e33*e31*e08+e33*e02*e37-e30*e05*e37-e30*e35*e07; A(9,17)=-e33*e31*e18-e33*e11*e38+e10*e34*e38+e30*e14*e38-e10*e35*e37-e30*e15*e37-e13*e31*e38+e13*e32*e37-e30*e35*e17+e33*e12*e37+e30*e34*e18+e33*e32*e17+e16*e31*e35-e16*e32*e34-e36*e12*e34-e36*e32*e14+e36*e11*e35+e36*e31*e15; A(9,18)=-e20*e35*e37+e20*e34*e38+e30*e24*e38-e30*e35*e27-e30*e25*e37+e30*e34*e28+e23*e32*e37-e23*e31*e38-e33*e21*e38-e33*e31*e28+e33*e22*e37+e33*e32*e27+e26*e31*e35-e26*e32*e34-e36*e22*e34-e36*e32*e24+e36*e21*e35+e36*e31*e25; A(9,19)=-e33*e31*e38-e30*e35*e37+e36*e31*e35+e33*e32*e37+e30*e34*e38-e36*e32*e34; } opengv/src/relative_pose/modules/fivept_kneip/0000775016516101651610000000000013344612246020572 5ustar dimadimaopengv/src/relative_pose/modules/fivept_kneip/reductors.cpp0000664016516101651610000045037513344612246023326 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::relative_pose::modules::fivept_kneip::groebnerRow30_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,152) / groebnerMatrix(30,152); groebnerMatrix(targetRow,152) = 0.0; groebnerMatrix(targetRow,153) -= factor * groebnerMatrix(30,153); groebnerMatrix(targetRow,155) -= factor * groebnerMatrix(30,155); groebnerMatrix(targetRow,156) -= factor * groebnerMatrix(30,156); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(30,157); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(30,158); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(30,159); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(30,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(30,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(30,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(30,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(30,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(30,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(30,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(30,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(30,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(30,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(30,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(30,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(30,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(30,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(30,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(30,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(30,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(30,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(30,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(30,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(30,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(30,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(30,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(30,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(30,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(30,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(30,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(30,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow31_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,153) / groebnerMatrix(31,153); groebnerMatrix(targetRow,153) = 0.0; groebnerMatrix(targetRow,155) -= factor * groebnerMatrix(31,155); groebnerMatrix(targetRow,156) -= factor * groebnerMatrix(31,156); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(31,157); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(31,158); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(31,159); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(31,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(31,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(31,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(31,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(31,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(31,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(31,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(31,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(31,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(31,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(31,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(31,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(31,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(31,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(31,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(31,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(31,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(31,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(31,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(31,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(31,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(31,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(31,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(31,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(31,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(31,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(31,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(31,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow32_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,155) / groebnerMatrix(32,155); groebnerMatrix(targetRow,155) = 0.0; groebnerMatrix(targetRow,156) -= factor * groebnerMatrix(32,156); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(32,157); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(32,158); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(32,159); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(32,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(32,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(32,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(32,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(32,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(32,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(32,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(32,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(32,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(32,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(32,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(32,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(32,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(32,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(32,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(32,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(32,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(32,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(32,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(32,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(32,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(32,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(32,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(32,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(32,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(32,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(32,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(32,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow33_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,156) / groebnerMatrix(33,156); groebnerMatrix(targetRow,156) = 0.0; groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(33,157); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(33,158); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(33,159); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(33,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(33,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(33,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(33,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(33,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(33,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(33,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(33,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(33,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(33,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(33,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(33,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(33,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(33,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(33,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(33,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(33,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(33,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(33,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(33,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(33,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(33,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(33,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(33,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(33,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(33,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(33,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(33,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow34_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,157) / groebnerMatrix(34,157); groebnerMatrix(targetRow,157) = 0.0; groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(34,158); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(34,159); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(34,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(34,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(34,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(34,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(34,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(34,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(34,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(34,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(34,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(34,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(34,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(34,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(34,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(34,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(34,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(34,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(34,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(34,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(34,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(34,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(34,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(34,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(34,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(34,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(34,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(34,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(34,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(34,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow35_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,158) / groebnerMatrix(35,158); groebnerMatrix(targetRow,158) = 0.0; groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(35,159); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(35,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(35,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(35,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(35,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(35,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(35,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(35,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(35,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(35,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(35,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(35,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(35,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(35,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(35,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(35,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(35,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(35,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(35,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(35,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(35,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(35,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(35,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(35,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(35,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(35,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(35,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(35,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(35,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow36_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,159) / groebnerMatrix(36,159); groebnerMatrix(targetRow,159) = 0.0; groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(36,160); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(36,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(36,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(36,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(36,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(36,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(36,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(36,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(36,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(36,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(36,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(36,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(36,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(36,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(36,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(36,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(36,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(36,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(36,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(36,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(36,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(36,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(36,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(36,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(36,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(36,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(36,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(36,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow37_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,160) / groebnerMatrix(37,160); groebnerMatrix(targetRow,160) = 0.0; groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(37,161); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(37,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(37,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(37,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(37,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(37,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(37,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(37,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(37,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(37,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(37,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(37,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(37,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(37,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(37,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(37,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(37,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(37,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(37,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(37,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(37,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(37,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(37,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(37,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(37,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(37,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(37,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow38_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,161) / groebnerMatrix(38,161); groebnerMatrix(targetRow,161) = 0.0; groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(38,162); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(38,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(38,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(38,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(38,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(38,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(38,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(38,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(38,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(38,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(38,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(38,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(38,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(38,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(38,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(38,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(38,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(38,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(38,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(38,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(38,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(38,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(38,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(38,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(38,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(38,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow38_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,116) / groebnerMatrix(38,161); groebnerMatrix(targetRow,116) = 0.0; groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(38,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(38,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(38,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(38,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(38,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(38,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(38,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(38,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(38,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(38,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(38,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(38,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(38,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(38,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(38,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(38,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(38,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(38,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(38,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(38,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(38,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(38,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(38,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(38,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(38,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(38,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow39_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,117) / groebnerMatrix(39,162); groebnerMatrix(targetRow,117) = 0.0; groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(39,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(39,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(39,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(39,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(39,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(39,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(39,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(39,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(39,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(39,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(39,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(39,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(39,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(39,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(39,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(39,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(39,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(39,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(39,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(39,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(39,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(39,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(39,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(39,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(39,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow39_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,162) / groebnerMatrix(39,162); groebnerMatrix(targetRow,162) = 0.0; groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(39,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(39,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(39,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(39,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(39,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(39,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(39,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(39,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(39,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(39,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(39,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(39,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(39,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(39,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(39,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(39,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(39,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(39,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(39,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(39,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(39,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(39,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(39,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(39,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(39,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow40_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,89) / groebnerMatrix(40,89); groebnerMatrix(targetRow,89) = 0.0; groebnerMatrix(targetRow,90) -= factor * groebnerMatrix(40,90); groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(40,92); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(40,93); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(40,95); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(40,96); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(40,125); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(40,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(40,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(40,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(40,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(40,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(40,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(40,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(40,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(40,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(40,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(40,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(40,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(40,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(40,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(40,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(40,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(40,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(40,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(40,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(40,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(40,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(40,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(40,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(40,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(40,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(40,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(40,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(40,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(40,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(40,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(40,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(40,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(40,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(40,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(40,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(40,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(40,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(40,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(40,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow33_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,111) / groebnerMatrix(33,156); groebnerMatrix(targetRow,111) = 0.0; groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(33,157); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(33,158); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(33,159); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(33,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(33,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(33,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(33,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(33,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(33,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(33,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(33,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(33,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(33,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(33,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(33,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(33,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(33,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(33,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(33,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(33,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(33,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(33,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(33,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(33,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(33,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(33,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(33,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(33,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(33,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(33,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(33,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow34_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,112) / groebnerMatrix(34,157); groebnerMatrix(targetRow,112) = 0.0; groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(34,158); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(34,159); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(34,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(34,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(34,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(34,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(34,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(34,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(34,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(34,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(34,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(34,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(34,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(34,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(34,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(34,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(34,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(34,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(34,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(34,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(34,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(34,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(34,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(34,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(34,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(34,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(34,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(34,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(34,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(34,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow35_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,113) / groebnerMatrix(35,158); groebnerMatrix(targetRow,113) = 0.0; groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(35,159); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(35,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(35,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(35,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(35,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(35,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(35,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(35,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(35,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(35,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(35,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(35,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(35,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(35,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(35,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(35,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(35,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(35,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(35,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(35,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(35,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(35,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(35,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(35,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(35,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(35,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(35,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(35,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(35,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow36_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,114) / groebnerMatrix(36,159); groebnerMatrix(targetRow,114) = 0.0; groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(36,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(36,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(36,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(36,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(36,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(36,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(36,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(36,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(36,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(36,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(36,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(36,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(36,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(36,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(36,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(36,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(36,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(36,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(36,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(36,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(36,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(36,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(36,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(36,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(36,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(36,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(36,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(36,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow37_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,115) / groebnerMatrix(37,160); groebnerMatrix(targetRow,115) = 0.0; groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(37,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(37,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(37,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(37,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(37,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(37,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(37,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(37,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(37,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(37,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(37,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(37,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(37,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(37,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(37,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(37,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(37,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(37,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(37,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(37,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(37,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(37,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(37,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(37,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(37,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(37,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(37,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow41_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,90) / groebnerMatrix(41,90); groebnerMatrix(targetRow,90) = 0.0; groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(41,92); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(41,93); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(41,95); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(41,96); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(41,125); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(41,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(41,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(41,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(41,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(41,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(41,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(41,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(41,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(41,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(41,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(41,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(41,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(41,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(41,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(41,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(41,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(41,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(41,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(41,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(41,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(41,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(41,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(41,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(41,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(41,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(41,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(41,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(41,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(41,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(41,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(41,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(41,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(41,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(41,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(41,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(41,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(41,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(41,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(41,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow32_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,110) / groebnerMatrix(32,155); groebnerMatrix(targetRow,110) = 0.0; groebnerMatrix(targetRow,111) -= factor * groebnerMatrix(32,156); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(32,157); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(32,158); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(32,159); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(32,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(32,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(32,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(32,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(32,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(32,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(32,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(32,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(32,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(32,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(32,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(32,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(32,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(32,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(32,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(32,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(32,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(32,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(32,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(32,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(32,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(32,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(32,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(32,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(32,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(32,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(32,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(32,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow42_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,92) / groebnerMatrix(42,92); groebnerMatrix(targetRow,92) = 0.0; groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(42,93); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(42,95); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(42,96); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(42,125); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(42,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(42,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(42,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(42,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(42,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(42,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(42,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(42,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(42,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(42,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(42,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(42,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(42,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(42,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(42,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(42,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(42,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(42,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(42,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(42,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(42,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(42,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(42,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(42,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(42,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(42,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(42,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(42,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(42,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(42,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(42,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(42,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(42,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(42,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(42,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(42,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(42,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(42,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(42,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow43_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,93) / groebnerMatrix(43,93); groebnerMatrix(targetRow,93) = 0.0; groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(43,95); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(43,96); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(43,125); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(43,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(43,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(43,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(43,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(43,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(43,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(43,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(43,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(43,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(43,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(43,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(43,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(43,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(43,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(43,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(43,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(43,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(43,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(43,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(43,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(43,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(43,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(43,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(43,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(43,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(43,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(43,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(43,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(43,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(43,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(43,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(43,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(43,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(43,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(43,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(43,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(43,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(43,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(43,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow31_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,108) / groebnerMatrix(31,153); groebnerMatrix(targetRow,108) = 0.0; groebnerMatrix(targetRow,110) -= factor * groebnerMatrix(31,155); groebnerMatrix(targetRow,111) -= factor * groebnerMatrix(31,156); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(31,157); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(31,158); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(31,159); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(31,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(31,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(31,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(31,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(31,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(31,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(31,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(31,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(31,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(31,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(31,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(31,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(31,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(31,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(31,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(31,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(31,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(31,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(31,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(31,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(31,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(31,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(31,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(31,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(31,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(31,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(31,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(31,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow44_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,95) / groebnerMatrix(44,95); groebnerMatrix(targetRow,95) = 0.0; groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(44,96); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(44,125); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(44,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(44,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(44,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(44,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(44,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(44,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(44,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(44,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(44,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(44,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(44,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(44,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(44,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(44,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(44,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(44,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(44,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(44,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(44,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(44,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(44,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(44,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(44,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(44,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(44,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(44,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(44,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(44,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(44,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(44,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(44,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(44,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(44,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(44,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(44,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(44,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(44,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(44,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(44,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow30_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,107) / groebnerMatrix(30,152); groebnerMatrix(targetRow,107) = 0.0; groebnerMatrix(targetRow,108) -= factor * groebnerMatrix(30,153); groebnerMatrix(targetRow,110) -= factor * groebnerMatrix(30,155); groebnerMatrix(targetRow,111) -= factor * groebnerMatrix(30,156); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(30,157); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(30,158); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(30,159); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(30,160); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(30,161); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(30,162); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(30,170); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(30,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(30,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(30,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(30,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(30,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(30,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(30,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(30,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(30,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(30,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(30,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(30,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(30,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(30,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(30,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(30,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(30,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(30,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(30,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(30,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(30,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(30,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(30,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(30,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow45_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,96) / groebnerMatrix(45,96); groebnerMatrix(targetRow,96) = 0.0; groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(45,125); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(45,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(45,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(45,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(45,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(45,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(45,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(45,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(45,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(45,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(45,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(45,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(45,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(45,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(45,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(45,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(45,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(45,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(45,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(45,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(45,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(45,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(45,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(45,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(45,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(45,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(45,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(45,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(45,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(45,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(45,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(45,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(45,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(45,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(45,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(45,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(45,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(45,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(45,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(45,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow46_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,125) / groebnerMatrix(46,125); groebnerMatrix(targetRow,125) = 0.0; groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(46,126); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(46,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(46,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(46,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(46,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(46,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(46,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(46,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(46,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(46,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(46,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(46,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(46,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(46,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(46,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(46,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(46,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(46,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(46,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(46,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(46,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(46,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(46,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(46,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(46,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(46,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(46,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(46,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(46,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(46,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(46,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(46,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(46,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(46,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(46,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(46,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(46,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(46,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(46,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow47_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,126) / groebnerMatrix(47,126); groebnerMatrix(targetRow,126) = 0.0; groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(47,128); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(47,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(47,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(47,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(47,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(47,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(47,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(47,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(47,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(47,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(47,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(47,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(47,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(47,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(47,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(47,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(47,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(47,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(47,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(47,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(47,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(47,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(47,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(47,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(47,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(47,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(47,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(47,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(47,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(47,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(47,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(47,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(47,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(47,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(47,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(47,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(47,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(47,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow48_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,128) / groebnerMatrix(48,128); groebnerMatrix(targetRow,128) = 0.0; groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(48,129); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(48,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(48,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(48,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(48,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(48,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(48,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(48,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(48,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(48,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(48,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(48,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(48,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(48,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(48,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(48,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(48,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(48,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(48,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(48,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(48,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(48,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(48,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(48,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(48,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(48,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(48,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(48,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(48,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(48,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(48,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(48,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(48,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(48,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(48,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(48,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(48,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow49_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,129) / groebnerMatrix(49,129); groebnerMatrix(targetRow,129) = 0.0; groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(49,131); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(49,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(49,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(49,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(49,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(49,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(49,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(49,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(49,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(49,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(49,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(49,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(49,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(49,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(49,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(49,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(49,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(49,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(49,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(49,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(49,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(49,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(49,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(49,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(49,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(49,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(49,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(49,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(49,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(49,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(49,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(49,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(49,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(49,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(49,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(49,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow50_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,131) / groebnerMatrix(50,131); groebnerMatrix(targetRow,131) = 0.0; groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(50,132); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(50,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(50,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(50,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(50,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(50,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(50,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(50,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(50,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(50,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(50,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(50,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(50,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(50,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(50,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(50,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(50,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(50,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(50,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(50,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(50,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(50,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(50,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(50,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(50,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(50,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(50,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(50,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(50,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(50,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(50,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(50,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(50,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(50,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(50,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow32_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,74) / groebnerMatrix(32,155); groebnerMatrix(targetRow,74) = 0.0; groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(32,156); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(32,157); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(32,158); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(32,159); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(32,160); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(32,161); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(32,162); groebnerMatrix(targetRow,89) -= factor * groebnerMatrix(32,170); groebnerMatrix(targetRow,90) -= factor * groebnerMatrix(32,171); groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(32,173); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(32,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(32,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(32,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(32,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(32,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(32,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(32,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(32,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(32,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(32,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(32,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(32,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(32,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(32,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(32,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(32,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(32,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(32,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(32,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(32,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(32,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(32,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow33_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,75) / groebnerMatrix(33,156); groebnerMatrix(targetRow,75) = 0.0; groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(33,157); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(33,158); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(33,159); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(33,160); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(33,161); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(33,162); groebnerMatrix(targetRow,89) -= factor * groebnerMatrix(33,170); groebnerMatrix(targetRow,90) -= factor * groebnerMatrix(33,171); groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(33,173); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(33,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(33,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(33,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(33,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(33,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(33,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(33,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(33,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(33,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(33,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(33,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(33,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(33,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(33,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(33,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(33,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(33,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(33,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(33,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(33,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(33,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(33,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow51_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,132) / groebnerMatrix(51,132); groebnerMatrix(targetRow,132) = 0.0; groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(51,133); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(51,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(51,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(51,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(51,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(51,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(51,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(51,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(51,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(51,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(51,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(51,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(51,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(51,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(51,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(51,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(51,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(51,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(51,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(51,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(51,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(51,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(51,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(51,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(51,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(51,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(51,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(51,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(51,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(51,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(51,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(51,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(51,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(51,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow52_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,133) / groebnerMatrix(52,133); groebnerMatrix(targetRow,133) = 0.0; groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(52,134); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(52,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(52,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(52,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(52,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(52,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(52,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(52,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(52,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(52,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(52,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(52,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(52,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(52,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(52,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(52,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(52,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(52,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(52,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(52,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(52,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(52,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(52,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(52,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(52,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(52,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(52,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(52,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(52,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(52,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(52,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(52,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(52,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow30_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,71) / groebnerMatrix(30,152); groebnerMatrix(targetRow,71) = 0.0; groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(30,153); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(30,155); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(30,156); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(30,157); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(30,158); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(30,159); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(30,160); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(30,161); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(30,162); groebnerMatrix(targetRow,89) -= factor * groebnerMatrix(30,170); groebnerMatrix(targetRow,90) -= factor * groebnerMatrix(30,171); groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(30,173); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(30,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(30,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(30,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(30,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(30,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(30,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(30,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(30,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(30,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(30,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(30,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(30,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(30,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(30,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(30,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(30,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(30,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(30,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(30,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(30,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(30,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(30,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow31_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,72) / groebnerMatrix(31,153); groebnerMatrix(targetRow,72) = 0.0; groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(31,155); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(31,156); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(31,157); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(31,158); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(31,159); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(31,160); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(31,161); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(31,162); groebnerMatrix(targetRow,89) -= factor * groebnerMatrix(31,170); groebnerMatrix(targetRow,90) -= factor * groebnerMatrix(31,171); groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(31,173); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(31,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(31,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(31,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(31,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(31,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(31,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(31,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(31,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(31,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(31,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(31,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(31,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(31,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(31,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(31,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(31,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(31,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(31,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(31,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(31,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(31,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(31,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow53_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,134) / groebnerMatrix(53,134); groebnerMatrix(targetRow,134) = 0.0; groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(53,135); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(53,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(53,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(53,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(53,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(53,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(53,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(53,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(53,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(53,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(53,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(53,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(53,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(53,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(53,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(53,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(53,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(53,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(53,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(53,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(53,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(53,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(53,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(53,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(53,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(53,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(53,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(53,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(53,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(53,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(53,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(53,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow39_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,38) / groebnerMatrix(39,162); groebnerMatrix(targetRow,38) = 0.0; groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(39,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(39,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(39,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(39,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(39,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(39,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(39,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(39,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(39,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(39,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(39,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(39,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(39,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(39,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(39,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(39,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(39,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(39,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(39,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(39,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(39,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(39,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(39,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(39,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(39,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow54_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,135) / groebnerMatrix(54,135); groebnerMatrix(targetRow,135) = 0.0; groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(54,136); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(54,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(54,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(54,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(54,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(54,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(54,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(54,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(54,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(54,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(54,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(54,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(54,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(54,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(54,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(54,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(54,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(54,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(54,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(54,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(54,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(54,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(54,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(54,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(54,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(54,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(54,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(54,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(54,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(54,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(54,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow38_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,37) / groebnerMatrix(38,161); groebnerMatrix(targetRow,37) = 0.0; groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(38,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(38,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(38,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(38,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(38,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(38,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(38,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(38,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(38,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(38,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(38,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(38,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(38,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(38,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(38,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(38,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(38,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(38,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(38,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(38,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(38,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(38,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(38,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(38,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(38,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(38,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow55_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,136) / groebnerMatrix(55,136); groebnerMatrix(targetRow,136) = 0.0; groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(55,137); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(55,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(55,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(55,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(55,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(55,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(55,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(55,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(55,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(55,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(55,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(55,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(55,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(55,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(55,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(55,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(55,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(55,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(55,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(55,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(55,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(55,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(55,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(55,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(55,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(55,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(55,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(55,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(55,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(55,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow37_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,36) / groebnerMatrix(37,160); groebnerMatrix(targetRow,36) = 0.0; groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(37,161); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(37,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(37,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(37,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(37,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(37,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(37,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(37,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(37,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(37,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(37,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(37,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(37,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(37,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(37,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(37,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(37,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(37,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(37,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(37,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(37,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(37,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(37,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(37,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(37,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(37,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(37,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow56_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,137) / groebnerMatrix(56,137); groebnerMatrix(targetRow,137) = 0.0; groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(56,138); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(56,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(56,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(56,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(56,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(56,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(56,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(56,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(56,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(56,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(56,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(56,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(56,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(56,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(56,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(56,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(56,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(56,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(56,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(56,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(56,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(56,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(56,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(56,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(56,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(56,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(56,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(56,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(56,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow36_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,35) / groebnerMatrix(36,159); groebnerMatrix(targetRow,35) = 0.0; groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(36,160); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(36,161); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(36,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(36,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(36,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(36,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(36,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(36,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(36,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(36,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(36,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(36,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(36,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(36,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(36,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(36,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(36,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(36,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(36,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(36,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(36,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(36,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(36,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(36,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(36,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(36,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(36,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(36,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow57_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,138) / groebnerMatrix(57,138); groebnerMatrix(targetRow,138) = 0.0; groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(57,139); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(57,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(57,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(57,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(57,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(57,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(57,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(57,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(57,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(57,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(57,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(57,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(57,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(57,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(57,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(57,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(57,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(57,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(57,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(57,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(57,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(57,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(57,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(57,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(57,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(57,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(57,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(57,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow35_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,34) / groebnerMatrix(35,158); groebnerMatrix(targetRow,34) = 0.0; groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(35,159); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(35,160); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(35,161); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(35,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(35,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(35,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(35,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(35,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(35,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(35,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(35,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(35,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(35,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(35,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(35,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(35,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(35,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(35,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(35,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(35,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(35,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(35,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(35,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(35,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(35,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(35,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(35,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(35,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(35,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow58_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,139) / groebnerMatrix(58,139); groebnerMatrix(targetRow,139) = 0.0; groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(58,140); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(58,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(58,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(58,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(58,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(58,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(58,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(58,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(58,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(58,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(58,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(58,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(58,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(58,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(58,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(58,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(58,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(58,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(58,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(58,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(58,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(58,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(58,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(58,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(58,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(58,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(58,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow34_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,33) / groebnerMatrix(34,157); groebnerMatrix(targetRow,33) = 0.0; groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(34,158); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(34,159); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(34,160); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(34,161); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(34,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(34,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(34,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(34,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(34,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(34,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(34,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(34,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(34,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(34,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(34,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(34,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(34,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(34,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(34,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(34,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(34,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(34,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(34,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(34,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(34,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(34,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(34,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(34,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(34,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(34,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow59_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,140) / groebnerMatrix(59,140); groebnerMatrix(targetRow,140) = 0.0; groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(59,141); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(59,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(59,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(59,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(59,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(59,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(59,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(59,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(59,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(59,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(59,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(59,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(59,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(59,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(59,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(59,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(59,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(59,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(59,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(59,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(59,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(59,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(59,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(59,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(59,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(59,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow33_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,32) / groebnerMatrix(33,156); groebnerMatrix(targetRow,32) = 0.0; groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(33,157); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(33,158); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(33,159); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(33,160); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(33,161); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(33,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(33,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(33,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(33,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(33,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(33,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(33,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(33,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(33,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(33,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(33,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(33,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(33,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(33,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(33,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(33,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(33,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(33,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(33,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(33,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(33,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(33,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(33,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(33,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(33,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(33,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow60_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,141) / groebnerMatrix(60,141); groebnerMatrix(targetRow,141) = 0.0; groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(60,170); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(60,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(60,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(60,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(60,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(60,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(60,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(60,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(60,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(60,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(60,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(60,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(60,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(60,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(60,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(60,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(60,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(60,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(60,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(60,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(60,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(60,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(60,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(60,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(60,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow61_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,89) / groebnerMatrix(61,170); groebnerMatrix(targetRow,89) = 0.0; groebnerMatrix(targetRow,90) -= factor * groebnerMatrix(61,171); groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(61,173); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(61,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(61,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(61,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(61,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(61,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(61,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(61,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(61,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(61,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(61,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(61,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(61,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(61,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(61,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(61,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(61,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(61,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(61,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(61,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(61,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(61,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(61,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow61_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,125) / groebnerMatrix(61,170); groebnerMatrix(targetRow,125) = 0.0; groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(61,171); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(61,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(61,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(61,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(61,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(61,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(61,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(61,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(61,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(61,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(61,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(61,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(61,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(61,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(61,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(61,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(61,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(61,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(61,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(61,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(61,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(61,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(61,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(61,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow61_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,170) / groebnerMatrix(61,170); groebnerMatrix(targetRow,170) = 0.0; groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(61,171); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(61,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(61,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(61,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(61,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(61,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(61,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(61,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(61,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(61,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(61,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(61,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(61,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(61,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(61,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(61,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(61,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(61,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(61,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(61,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(61,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(61,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(61,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(61,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow32_000100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,31) / groebnerMatrix(32,155); groebnerMatrix(targetRow,31) = 0.0; groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(32,156); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(32,157); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(32,158); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(32,159); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(32,160); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(32,161); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(32,162); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(32,170); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(32,171); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(32,173); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(32,174); groebnerMatrix(targetRow,87) -= factor * groebnerMatrix(32,176); groebnerMatrix(targetRow,94) -= factor * groebnerMatrix(32,177); groebnerMatrix(targetRow,112) -= factor * groebnerMatrix(32,178); groebnerMatrix(targetRow,113) -= factor * groebnerMatrix(32,179); groebnerMatrix(targetRow,114) -= factor * groebnerMatrix(32,180); groebnerMatrix(targetRow,115) -= factor * groebnerMatrix(32,181); groebnerMatrix(targetRow,116) -= factor * groebnerMatrix(32,182); groebnerMatrix(targetRow,117) -= factor * groebnerMatrix(32,183); groebnerMatrix(targetRow,123) -= factor * groebnerMatrix(32,184); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(32,185); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(32,186); groebnerMatrix(targetRow,157) -= factor * groebnerMatrix(32,187); groebnerMatrix(targetRow,158) -= factor * groebnerMatrix(32,188); groebnerMatrix(targetRow,159) -= factor * groebnerMatrix(32,189); groebnerMatrix(targetRow,160) -= factor * groebnerMatrix(32,190); groebnerMatrix(targetRow,161) -= factor * groebnerMatrix(32,191); groebnerMatrix(targetRow,162) -= factor * groebnerMatrix(32,192); groebnerMatrix(targetRow,168) -= factor * groebnerMatrix(32,193); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(32,194); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(32,195); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(32,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow62_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,90) / groebnerMatrix(62,171); groebnerMatrix(targetRow,90) = 0.0; groebnerMatrix(targetRow,92) -= factor * groebnerMatrix(62,173); groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(62,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(62,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(62,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(62,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(62,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(62,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(62,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(62,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(62,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(62,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(62,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(62,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(62,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(62,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(62,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(62,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(62,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(62,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(62,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(62,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(62,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(62,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow62_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,126) / groebnerMatrix(62,171); groebnerMatrix(targetRow,126) = 0.0; groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(62,173); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(62,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(62,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(62,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(62,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(62,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(62,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(62,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(62,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(62,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(62,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(62,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(62,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(62,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(62,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(62,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(62,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(62,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(62,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(62,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(62,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(62,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(62,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow62_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,171) / groebnerMatrix(62,171); groebnerMatrix(targetRow,171) = 0.0; groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(62,173); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(62,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(62,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(62,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(62,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(62,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(62,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(62,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(62,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(62,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(62,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(62,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(62,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(62,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(62,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(62,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(62,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(62,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(62,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(62,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(62,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(62,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(62,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow63_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,128) / groebnerMatrix(63,173); groebnerMatrix(targetRow,128) = 0.0; groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(63,174); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(63,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(63,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(63,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(63,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(63,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(63,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(63,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(63,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(63,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(63,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(63,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(63,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(63,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(63,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(63,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(63,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(63,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(63,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(63,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(63,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(63,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow63_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,173) / groebnerMatrix(63,173); groebnerMatrix(targetRow,173) = 0.0; groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(63,174); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(63,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(63,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(63,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(63,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(63,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(63,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(63,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(63,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(63,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(63,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(63,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(63,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(63,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(63,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(63,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(63,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(63,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(63,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(63,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(63,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(63,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow63_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,92) / groebnerMatrix(63,173); groebnerMatrix(targetRow,92) = 0.0; groebnerMatrix(targetRow,93) -= factor * groebnerMatrix(63,174); groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(63,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(63,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(63,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(63,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(63,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(63,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(63,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(63,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(63,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(63,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(63,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(63,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(63,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(63,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(63,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(63,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(63,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(63,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(63,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(63,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(63,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow64_010000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,93) / groebnerMatrix(64,174); groebnerMatrix(targetRow,93) = 0.0; groebnerMatrix(targetRow,95) -= factor * groebnerMatrix(64,176); groebnerMatrix(targetRow,96) -= factor * groebnerMatrix(64,177); groebnerMatrix(targetRow,125) -= factor * groebnerMatrix(64,178); groebnerMatrix(targetRow,126) -= factor * groebnerMatrix(64,179); groebnerMatrix(targetRow,127) -= factor * groebnerMatrix(64,180); groebnerMatrix(targetRow,128) -= factor * groebnerMatrix(64,181); groebnerMatrix(targetRow,129) -= factor * groebnerMatrix(64,182); groebnerMatrix(targetRow,130) -= factor * groebnerMatrix(64,183); groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(64,184); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(64,185); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(64,186); groebnerMatrix(targetRow,170) -= factor * groebnerMatrix(64,187); groebnerMatrix(targetRow,171) -= factor * groebnerMatrix(64,188); groebnerMatrix(targetRow,172) -= factor * groebnerMatrix(64,189); groebnerMatrix(targetRow,173) -= factor * groebnerMatrix(64,190); groebnerMatrix(targetRow,174) -= factor * groebnerMatrix(64,191); groebnerMatrix(targetRow,175) -= factor * groebnerMatrix(64,192); groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(64,193); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(64,194); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(64,195); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(64,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow64_100000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,129) / groebnerMatrix(64,174); groebnerMatrix(targetRow,129) = 0.0; groebnerMatrix(targetRow,131) -= factor * groebnerMatrix(64,176); groebnerMatrix(targetRow,132) -= factor * groebnerMatrix(64,177); groebnerMatrix(targetRow,133) -= factor * groebnerMatrix(64,178); groebnerMatrix(targetRow,134) -= factor * groebnerMatrix(64,179); groebnerMatrix(targetRow,135) -= factor * groebnerMatrix(64,180); groebnerMatrix(targetRow,136) -= factor * groebnerMatrix(64,181); groebnerMatrix(targetRow,137) -= factor * groebnerMatrix(64,182); groebnerMatrix(targetRow,138) -= factor * groebnerMatrix(64,183); groebnerMatrix(targetRow,139) -= factor * groebnerMatrix(64,184); groebnerMatrix(targetRow,140) -= factor * groebnerMatrix(64,185); groebnerMatrix(targetRow,141) -= factor * groebnerMatrix(64,186); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(64,187); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(64,188); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(64,189); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(64,190); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(64,191); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(64,192); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(64,193); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(64,194); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(64,195); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(64,196); } void opengv::relative_pose::modules::fivept_kneip::groebnerRow64_000000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,174) / groebnerMatrix(64,174); groebnerMatrix(targetRow,174) = 0.0; groebnerMatrix(targetRow,176) -= factor * groebnerMatrix(64,176); groebnerMatrix(targetRow,177) -= factor * groebnerMatrix(64,177); groebnerMatrix(targetRow,178) -= factor * groebnerMatrix(64,178); groebnerMatrix(targetRow,179) -= factor * groebnerMatrix(64,179); groebnerMatrix(targetRow,180) -= factor * groebnerMatrix(64,180); groebnerMatrix(targetRow,181) -= factor * groebnerMatrix(64,181); groebnerMatrix(targetRow,182) -= factor * groebnerMatrix(64,182); groebnerMatrix(targetRow,183) -= factor * groebnerMatrix(64,183); groebnerMatrix(targetRow,184) -= factor * groebnerMatrix(64,184); groebnerMatrix(targetRow,185) -= factor * groebnerMatrix(64,185); groebnerMatrix(targetRow,186) -= factor * groebnerMatrix(64,186); groebnerMatrix(targetRow,187) -= factor * groebnerMatrix(64,187); groebnerMatrix(targetRow,188) -= factor * groebnerMatrix(64,188); groebnerMatrix(targetRow,189) -= factor * groebnerMatrix(64,189); groebnerMatrix(targetRow,190) -= factor * groebnerMatrix(64,190); groebnerMatrix(targetRow,191) -= factor * groebnerMatrix(64,191); groebnerMatrix(targetRow,192) -= factor * groebnerMatrix(64,192); groebnerMatrix(targetRow,193) -= factor * groebnerMatrix(64,193); groebnerMatrix(targetRow,194) -= factor * groebnerMatrix(64,194); groebnerMatrix(targetRow,195) -= factor * groebnerMatrix(64,195); groebnerMatrix(targetRow,196) -= factor * groebnerMatrix(64,196); } opengv/src/relative_pose/modules/fivept_kneip/spolynomials.cpp0000664016516101651610000062646313344612246024050 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::relative_pose::modules::fivept_kneip::sPolynomial30( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(30,1) = (groebnerMatrix(0,1)/(groebnerMatrix(0,0))-groebnerMatrix(1,1)/(groebnerMatrix(1,0))); groebnerMatrix(30,2) = (groebnerMatrix(0,2)/(groebnerMatrix(0,0))-groebnerMatrix(1,2)/(groebnerMatrix(1,0))); groebnerMatrix(30,3) = (groebnerMatrix(0,3)/(groebnerMatrix(0,0))-groebnerMatrix(1,3)/(groebnerMatrix(1,0))); groebnerMatrix(30,4) = (groebnerMatrix(0,4)/(groebnerMatrix(0,0))-groebnerMatrix(1,4)/(groebnerMatrix(1,0))); groebnerMatrix(30,5) = (groebnerMatrix(0,5)/(groebnerMatrix(0,0))-groebnerMatrix(1,5)/(groebnerMatrix(1,0))); groebnerMatrix(30,6) = (groebnerMatrix(0,6)/(groebnerMatrix(0,0))-groebnerMatrix(1,6)/(groebnerMatrix(1,0))); groebnerMatrix(30,8) = (groebnerMatrix(0,8)/(groebnerMatrix(0,0))-groebnerMatrix(1,8)/(groebnerMatrix(1,0))); groebnerMatrix(30,10) = (groebnerMatrix(0,10)/(groebnerMatrix(0,0))-groebnerMatrix(1,10)/(groebnerMatrix(1,0))); groebnerMatrix(30,11) = (groebnerMatrix(0,11)/(groebnerMatrix(0,0))-groebnerMatrix(1,11)/(groebnerMatrix(1,0))); groebnerMatrix(30,12) = (groebnerMatrix(0,12)/(groebnerMatrix(0,0))-groebnerMatrix(1,12)/(groebnerMatrix(1,0))); groebnerMatrix(30,13) = (groebnerMatrix(0,13)/(groebnerMatrix(0,0))-groebnerMatrix(1,13)/(groebnerMatrix(1,0))); groebnerMatrix(30,14) = (groebnerMatrix(0,14)/(groebnerMatrix(0,0))-groebnerMatrix(1,14)/(groebnerMatrix(1,0))); groebnerMatrix(30,15) = (groebnerMatrix(0,15)/(groebnerMatrix(0,0))-groebnerMatrix(1,15)/(groebnerMatrix(1,0))); groebnerMatrix(30,16) = (groebnerMatrix(0,16)/(groebnerMatrix(0,0))-groebnerMatrix(1,16)/(groebnerMatrix(1,0))); groebnerMatrix(30,18) = (groebnerMatrix(0,18)/(groebnerMatrix(0,0))-groebnerMatrix(1,18)/(groebnerMatrix(1,0))); groebnerMatrix(30,19) = (groebnerMatrix(0,19)/(groebnerMatrix(0,0))-groebnerMatrix(1,19)/(groebnerMatrix(1,0))); groebnerMatrix(30,20) = (groebnerMatrix(0,20)/(groebnerMatrix(0,0))-groebnerMatrix(1,20)/(groebnerMatrix(1,0))); groebnerMatrix(30,21) = (groebnerMatrix(0,21)/(groebnerMatrix(0,0))-groebnerMatrix(1,21)/(groebnerMatrix(1,0))); groebnerMatrix(30,22) = (groebnerMatrix(0,22)/(groebnerMatrix(0,0))-groebnerMatrix(1,22)/(groebnerMatrix(1,0))); groebnerMatrix(30,23) = (groebnerMatrix(0,23)/(groebnerMatrix(0,0))-groebnerMatrix(1,23)/(groebnerMatrix(1,0))); groebnerMatrix(30,25) = (groebnerMatrix(0,25)/(groebnerMatrix(0,0))-groebnerMatrix(1,25)/(groebnerMatrix(1,0))); groebnerMatrix(30,26) = (groebnerMatrix(0,26)/(groebnerMatrix(0,0))-groebnerMatrix(1,26)/(groebnerMatrix(1,0))); groebnerMatrix(30,27) = (groebnerMatrix(0,27)/(groebnerMatrix(0,0))-groebnerMatrix(1,27)/(groebnerMatrix(1,0))); groebnerMatrix(30,28) = (groebnerMatrix(0,28)/(groebnerMatrix(0,0))-groebnerMatrix(1,28)/(groebnerMatrix(1,0))); groebnerMatrix(30,29) = (groebnerMatrix(0,29)/(groebnerMatrix(0,0))-groebnerMatrix(1,29)/(groebnerMatrix(1,0))); groebnerMatrix(30,30) = (groebnerMatrix(0,30)/(groebnerMatrix(0,0))-groebnerMatrix(1,30)/(groebnerMatrix(1,0))); groebnerMatrix(30,33) = (groebnerMatrix(0,33)/(groebnerMatrix(0,0))-groebnerMatrix(1,33)/(groebnerMatrix(1,0))); groebnerMatrix(30,34) = (groebnerMatrix(0,34)/(groebnerMatrix(0,0))-groebnerMatrix(1,34)/(groebnerMatrix(1,0))); groebnerMatrix(30,39) = (groebnerMatrix(0,39)/(groebnerMatrix(0,0))-groebnerMatrix(1,39)/(groebnerMatrix(1,0))); groebnerMatrix(30,40) = (groebnerMatrix(0,40)/(groebnerMatrix(0,0))-groebnerMatrix(1,40)/(groebnerMatrix(1,0))); groebnerMatrix(30,41) = (groebnerMatrix(0,41)/(groebnerMatrix(0,0))-groebnerMatrix(1,41)/(groebnerMatrix(1,0))); groebnerMatrix(30,42) = (groebnerMatrix(0,42)/(groebnerMatrix(0,0))-groebnerMatrix(1,42)/(groebnerMatrix(1,0))); groebnerMatrix(30,43) = (groebnerMatrix(0,43)/(groebnerMatrix(0,0))-groebnerMatrix(1,43)/(groebnerMatrix(1,0))); groebnerMatrix(30,44) = (groebnerMatrix(0,44)/(groebnerMatrix(0,0))-groebnerMatrix(1,44)/(groebnerMatrix(1,0))); groebnerMatrix(30,45) = (groebnerMatrix(0,45)/(groebnerMatrix(0,0))-groebnerMatrix(1,45)/(groebnerMatrix(1,0))); groebnerMatrix(30,46) = (groebnerMatrix(0,46)/(groebnerMatrix(0,0))-groebnerMatrix(1,46)/(groebnerMatrix(1,0))); groebnerMatrix(30,47) = (groebnerMatrix(0,47)/(groebnerMatrix(0,0))-groebnerMatrix(1,47)/(groebnerMatrix(1,0))); groebnerMatrix(30,48) = (groebnerMatrix(0,48)/(groebnerMatrix(0,0))-groebnerMatrix(1,48)/(groebnerMatrix(1,0))); groebnerMatrix(30,49) = (groebnerMatrix(0,49)/(groebnerMatrix(0,0))-groebnerMatrix(1,49)/(groebnerMatrix(1,0))); groebnerMatrix(30,50) = (groebnerMatrix(0,50)/(groebnerMatrix(0,0))-groebnerMatrix(1,50)/(groebnerMatrix(1,0))); groebnerMatrix(30,51) = (groebnerMatrix(0,51)/(groebnerMatrix(0,0))-groebnerMatrix(1,51)/(groebnerMatrix(1,0))); groebnerMatrix(30,52) = (groebnerMatrix(0,52)/(groebnerMatrix(0,0))-groebnerMatrix(1,52)/(groebnerMatrix(1,0))); groebnerMatrix(30,53) = (groebnerMatrix(0,53)/(groebnerMatrix(0,0))-groebnerMatrix(1,53)/(groebnerMatrix(1,0))); groebnerMatrix(30,54) = (groebnerMatrix(0,54)/(groebnerMatrix(0,0))-groebnerMatrix(1,54)/(groebnerMatrix(1,0))); groebnerMatrix(30,55) = (groebnerMatrix(0,55)/(groebnerMatrix(0,0))-groebnerMatrix(1,55)/(groebnerMatrix(1,0))); groebnerMatrix(30,56) = (groebnerMatrix(0,56)/(groebnerMatrix(0,0))-groebnerMatrix(1,56)/(groebnerMatrix(1,0))); groebnerMatrix(30,57) = (groebnerMatrix(0,57)/(groebnerMatrix(0,0))-groebnerMatrix(1,57)/(groebnerMatrix(1,0))); groebnerMatrix(30,58) = (groebnerMatrix(0,58)/(groebnerMatrix(0,0))-groebnerMatrix(1,58)/(groebnerMatrix(1,0))); groebnerMatrix(30,59) = (groebnerMatrix(0,59)/(groebnerMatrix(0,0))-groebnerMatrix(1,59)/(groebnerMatrix(1,0))); groebnerMatrix(30,60) = (groebnerMatrix(0,60)/(groebnerMatrix(0,0))-groebnerMatrix(1,60)/(groebnerMatrix(1,0))); groebnerMatrix(30,61) = (groebnerMatrix(0,61)/(groebnerMatrix(0,0))-groebnerMatrix(1,61)/(groebnerMatrix(1,0))); groebnerMatrix(30,62) = (groebnerMatrix(0,62)/(groebnerMatrix(0,0))-groebnerMatrix(1,62)/(groebnerMatrix(1,0))); groebnerMatrix(30,64) = (groebnerMatrix(0,64)/(groebnerMatrix(0,0))-groebnerMatrix(1,64)/(groebnerMatrix(1,0))); groebnerMatrix(30,65) = (groebnerMatrix(0,65)/(groebnerMatrix(0,0))-groebnerMatrix(1,65)/(groebnerMatrix(1,0))); groebnerMatrix(30,66) = (groebnerMatrix(0,66)/(groebnerMatrix(0,0))-groebnerMatrix(1,66)/(groebnerMatrix(1,0))); groebnerMatrix(30,67) = (groebnerMatrix(0,67)/(groebnerMatrix(0,0))-groebnerMatrix(1,67)/(groebnerMatrix(1,0))); groebnerMatrix(30,68) = (groebnerMatrix(0,68)/(groebnerMatrix(0,0))-groebnerMatrix(1,68)/(groebnerMatrix(1,0))); groebnerMatrix(30,69) = (groebnerMatrix(0,69)/(groebnerMatrix(0,0))-groebnerMatrix(1,69)/(groebnerMatrix(1,0))); groebnerMatrix(30,70) = (groebnerMatrix(0,70)/(groebnerMatrix(0,0))-groebnerMatrix(1,70)/(groebnerMatrix(1,0))); groebnerMatrix(30,71) = (groebnerMatrix(0,71)/(groebnerMatrix(0,0))-groebnerMatrix(1,71)/(groebnerMatrix(1,0))); groebnerMatrix(30,73) = (groebnerMatrix(0,73)/(groebnerMatrix(0,0))-groebnerMatrix(1,73)/(groebnerMatrix(1,0))); groebnerMatrix(30,74) = (groebnerMatrix(0,74)/(groebnerMatrix(0,0))-groebnerMatrix(1,74)/(groebnerMatrix(1,0))); groebnerMatrix(30,76) = (groebnerMatrix(0,76)/(groebnerMatrix(0,0))-groebnerMatrix(1,76)/(groebnerMatrix(1,0))); groebnerMatrix(30,77) = (groebnerMatrix(0,77)/(groebnerMatrix(0,0))-groebnerMatrix(1,77)/(groebnerMatrix(1,0))); groebnerMatrix(30,78) = (groebnerMatrix(0,78)/(groebnerMatrix(0,0))-groebnerMatrix(1,78)/(groebnerMatrix(1,0))); groebnerMatrix(30,79) = (groebnerMatrix(0,79)/(groebnerMatrix(0,0))-groebnerMatrix(1,79)/(groebnerMatrix(1,0))); groebnerMatrix(30,80) = (groebnerMatrix(0,80)/(groebnerMatrix(0,0))-groebnerMatrix(1,80)/(groebnerMatrix(1,0))); groebnerMatrix(30,81) = (groebnerMatrix(0,81)/(groebnerMatrix(0,0))-groebnerMatrix(1,81)/(groebnerMatrix(1,0))); groebnerMatrix(30,82) = (groebnerMatrix(0,82)/(groebnerMatrix(0,0))-groebnerMatrix(1,82)/(groebnerMatrix(1,0))); groebnerMatrix(30,83) = (groebnerMatrix(0,83)/(groebnerMatrix(0,0))-groebnerMatrix(1,83)/(groebnerMatrix(1,0))); groebnerMatrix(30,84) = (groebnerMatrix(0,84)/(groebnerMatrix(0,0))-groebnerMatrix(1,84)/(groebnerMatrix(1,0))); groebnerMatrix(30,85) = (groebnerMatrix(0,85)/(groebnerMatrix(0,0))-groebnerMatrix(1,85)/(groebnerMatrix(1,0))); groebnerMatrix(30,86) = (groebnerMatrix(0,86)/(groebnerMatrix(0,0))-groebnerMatrix(1,86)/(groebnerMatrix(1,0))); groebnerMatrix(30,87) = (groebnerMatrix(0,87)/(groebnerMatrix(0,0))-groebnerMatrix(1,87)/(groebnerMatrix(1,0))); groebnerMatrix(30,89) = (groebnerMatrix(0,89)/(groebnerMatrix(0,0))-groebnerMatrix(1,89)/(groebnerMatrix(1,0))); groebnerMatrix(30,91) = (groebnerMatrix(0,91)/(groebnerMatrix(0,0))-groebnerMatrix(1,91)/(groebnerMatrix(1,0))); groebnerMatrix(30,92) = (groebnerMatrix(0,92)/(groebnerMatrix(0,0))-groebnerMatrix(1,92)/(groebnerMatrix(1,0))); groebnerMatrix(30,94) = (groebnerMatrix(0,94)/(groebnerMatrix(0,0))-groebnerMatrix(1,94)/(groebnerMatrix(1,0))); groebnerMatrix(30,97) = (groebnerMatrix(0,97)/(groebnerMatrix(0,0))-groebnerMatrix(1,97)/(groebnerMatrix(1,0))); groebnerMatrix(30,98) = (groebnerMatrix(0,98)/(groebnerMatrix(0,0))-groebnerMatrix(1,98)/(groebnerMatrix(1,0))); groebnerMatrix(30,99) = (groebnerMatrix(0,99)/(groebnerMatrix(0,0))-groebnerMatrix(1,99)/(groebnerMatrix(1,0))); groebnerMatrix(30,100) = (groebnerMatrix(0,100)/(groebnerMatrix(0,0))-groebnerMatrix(1,100)/(groebnerMatrix(1,0))); groebnerMatrix(30,101) = (groebnerMatrix(0,101)/(groebnerMatrix(0,0))-groebnerMatrix(1,101)/(groebnerMatrix(1,0))); groebnerMatrix(30,103) = (groebnerMatrix(0,103)/(groebnerMatrix(0,0))-groebnerMatrix(1,103)/(groebnerMatrix(1,0))); groebnerMatrix(30,104) = (groebnerMatrix(0,104)/(groebnerMatrix(0,0))-groebnerMatrix(1,104)/(groebnerMatrix(1,0))); groebnerMatrix(30,105) = (groebnerMatrix(0,105)/(groebnerMatrix(0,0))-groebnerMatrix(1,105)/(groebnerMatrix(1,0))); groebnerMatrix(30,106) = (groebnerMatrix(0,106)/(groebnerMatrix(0,0))-groebnerMatrix(1,106)/(groebnerMatrix(1,0))); groebnerMatrix(30,107) = (groebnerMatrix(0,107)/(groebnerMatrix(0,0))-groebnerMatrix(1,107)/(groebnerMatrix(1,0))); groebnerMatrix(30,108) = (groebnerMatrix(0,108)/(groebnerMatrix(0,0))-groebnerMatrix(1,108)/(groebnerMatrix(1,0))); groebnerMatrix(30,109) = (groebnerMatrix(0,109)/(groebnerMatrix(0,0))-groebnerMatrix(1,109)/(groebnerMatrix(1,0))); groebnerMatrix(30,110) = (groebnerMatrix(0,110)/(groebnerMatrix(0,0))-groebnerMatrix(1,110)/(groebnerMatrix(1,0))); groebnerMatrix(30,111) = (groebnerMatrix(0,111)/(groebnerMatrix(0,0))-groebnerMatrix(1,111)/(groebnerMatrix(1,0))); groebnerMatrix(30,112) = (groebnerMatrix(0,112)/(groebnerMatrix(0,0))-groebnerMatrix(1,112)/(groebnerMatrix(1,0))); groebnerMatrix(30,113) = (groebnerMatrix(0,113)/(groebnerMatrix(0,0))-groebnerMatrix(1,113)/(groebnerMatrix(1,0))); groebnerMatrix(30,115) = (groebnerMatrix(0,115)/(groebnerMatrix(0,0))-groebnerMatrix(1,115)/(groebnerMatrix(1,0))); groebnerMatrix(30,116) = (groebnerMatrix(0,116)/(groebnerMatrix(0,0))-groebnerMatrix(1,116)/(groebnerMatrix(1,0))); groebnerMatrix(30,118) = (groebnerMatrix(0,118)/(groebnerMatrix(0,0))-groebnerMatrix(1,118)/(groebnerMatrix(1,0))); groebnerMatrix(30,119) = (groebnerMatrix(0,119)/(groebnerMatrix(0,0))-groebnerMatrix(1,119)/(groebnerMatrix(1,0))); groebnerMatrix(30,120) = (groebnerMatrix(0,120)/(groebnerMatrix(0,0))-groebnerMatrix(1,120)/(groebnerMatrix(1,0))); groebnerMatrix(30,121) = (groebnerMatrix(0,121)/(groebnerMatrix(0,0))-groebnerMatrix(1,121)/(groebnerMatrix(1,0))); groebnerMatrix(30,122) = (groebnerMatrix(0,122)/(groebnerMatrix(0,0))-groebnerMatrix(1,122)/(groebnerMatrix(1,0))); groebnerMatrix(30,123) = (groebnerMatrix(0,123)/(groebnerMatrix(0,0))-groebnerMatrix(1,123)/(groebnerMatrix(1,0))); groebnerMatrix(30,125) = (groebnerMatrix(0,125)/(groebnerMatrix(0,0))-groebnerMatrix(1,125)/(groebnerMatrix(1,0))); groebnerMatrix(30,126) = (groebnerMatrix(0,126)/(groebnerMatrix(0,0))-groebnerMatrix(1,126)/(groebnerMatrix(1,0))); groebnerMatrix(30,127) = (groebnerMatrix(0,127)/(groebnerMatrix(0,0))-groebnerMatrix(1,127)/(groebnerMatrix(1,0))); groebnerMatrix(30,128) = (groebnerMatrix(0,128)/(groebnerMatrix(0,0))-groebnerMatrix(1,128)/(groebnerMatrix(1,0))); groebnerMatrix(30,129) = (groebnerMatrix(0,129)/(groebnerMatrix(0,0))-groebnerMatrix(1,129)/(groebnerMatrix(1,0))); groebnerMatrix(30,130) = (groebnerMatrix(0,130)/(groebnerMatrix(0,0))-groebnerMatrix(1,130)/(groebnerMatrix(1,0))); groebnerMatrix(30,133) = (groebnerMatrix(0,133)/(groebnerMatrix(0,0))-groebnerMatrix(1,133)/(groebnerMatrix(1,0))); groebnerMatrix(30,134) = (groebnerMatrix(0,134)/(groebnerMatrix(0,0))-groebnerMatrix(1,134)/(groebnerMatrix(1,0))); groebnerMatrix(30,136) = (groebnerMatrix(0,136)/(groebnerMatrix(0,0))-groebnerMatrix(1,136)/(groebnerMatrix(1,0))); groebnerMatrix(30,137) = (groebnerMatrix(0,137)/(groebnerMatrix(0,0))-groebnerMatrix(1,137)/(groebnerMatrix(1,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial31( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(31,1) = (groebnerMatrix(1,1)/(groebnerMatrix(1,0))-groebnerMatrix(2,1)/(groebnerMatrix(2,0))); groebnerMatrix(31,2) = (groebnerMatrix(1,2)/(groebnerMatrix(1,0))-groebnerMatrix(2,2)/(groebnerMatrix(2,0))); groebnerMatrix(31,3) = (groebnerMatrix(1,3)/(groebnerMatrix(1,0))-groebnerMatrix(2,3)/(groebnerMatrix(2,0))); groebnerMatrix(31,4) = (groebnerMatrix(1,4)/(groebnerMatrix(1,0))-groebnerMatrix(2,4)/(groebnerMatrix(2,0))); groebnerMatrix(31,5) = (groebnerMatrix(1,5)/(groebnerMatrix(1,0))-groebnerMatrix(2,5)/(groebnerMatrix(2,0))); groebnerMatrix(31,6) = (groebnerMatrix(1,6)/(groebnerMatrix(1,0))-groebnerMatrix(2,6)/(groebnerMatrix(2,0))); groebnerMatrix(31,8) = (groebnerMatrix(1,8)/(groebnerMatrix(1,0))-groebnerMatrix(2,8)/(groebnerMatrix(2,0))); groebnerMatrix(31,10) = (groebnerMatrix(1,10)/(groebnerMatrix(1,0))-groebnerMatrix(2,10)/(groebnerMatrix(2,0))); groebnerMatrix(31,11) = (groebnerMatrix(1,11)/(groebnerMatrix(1,0))-groebnerMatrix(2,11)/(groebnerMatrix(2,0))); groebnerMatrix(31,12) = (groebnerMatrix(1,12)/(groebnerMatrix(1,0))-groebnerMatrix(2,12)/(groebnerMatrix(2,0))); groebnerMatrix(31,13) = (groebnerMatrix(1,13)/(groebnerMatrix(1,0))-groebnerMatrix(2,13)/(groebnerMatrix(2,0))); groebnerMatrix(31,14) = (groebnerMatrix(1,14)/(groebnerMatrix(1,0))-groebnerMatrix(2,14)/(groebnerMatrix(2,0))); groebnerMatrix(31,15) = (groebnerMatrix(1,15)/(groebnerMatrix(1,0))-groebnerMatrix(2,15)/(groebnerMatrix(2,0))); groebnerMatrix(31,16) = (groebnerMatrix(1,16)/(groebnerMatrix(1,0))-groebnerMatrix(2,16)/(groebnerMatrix(2,0))); groebnerMatrix(31,18) = (groebnerMatrix(1,18)/(groebnerMatrix(1,0))-groebnerMatrix(2,18)/(groebnerMatrix(2,0))); groebnerMatrix(31,19) = (groebnerMatrix(1,19)/(groebnerMatrix(1,0))-groebnerMatrix(2,19)/(groebnerMatrix(2,0))); groebnerMatrix(31,20) = (groebnerMatrix(1,20)/(groebnerMatrix(1,0))-groebnerMatrix(2,20)/(groebnerMatrix(2,0))); groebnerMatrix(31,21) = (groebnerMatrix(1,21)/(groebnerMatrix(1,0))-groebnerMatrix(2,21)/(groebnerMatrix(2,0))); groebnerMatrix(31,22) = (groebnerMatrix(1,22)/(groebnerMatrix(1,0))-groebnerMatrix(2,22)/(groebnerMatrix(2,0))); groebnerMatrix(31,23) = (groebnerMatrix(1,23)/(groebnerMatrix(1,0))-groebnerMatrix(2,23)/(groebnerMatrix(2,0))); groebnerMatrix(31,25) = (groebnerMatrix(1,25)/(groebnerMatrix(1,0))-groebnerMatrix(2,25)/(groebnerMatrix(2,0))); groebnerMatrix(31,26) = (groebnerMatrix(1,26)/(groebnerMatrix(1,0))-groebnerMatrix(2,26)/(groebnerMatrix(2,0))); groebnerMatrix(31,27) = (groebnerMatrix(1,27)/(groebnerMatrix(1,0))-groebnerMatrix(2,27)/(groebnerMatrix(2,0))); groebnerMatrix(31,28) = (groebnerMatrix(1,28)/(groebnerMatrix(1,0))-groebnerMatrix(2,28)/(groebnerMatrix(2,0))); groebnerMatrix(31,29) = (groebnerMatrix(1,29)/(groebnerMatrix(1,0))-groebnerMatrix(2,29)/(groebnerMatrix(2,0))); groebnerMatrix(31,30) = (groebnerMatrix(1,30)/(groebnerMatrix(1,0))-groebnerMatrix(2,30)/(groebnerMatrix(2,0))); groebnerMatrix(31,33) = (groebnerMatrix(1,33)/(groebnerMatrix(1,0))-groebnerMatrix(2,33)/(groebnerMatrix(2,0))); groebnerMatrix(31,34) = (groebnerMatrix(1,34)/(groebnerMatrix(1,0))-groebnerMatrix(2,34)/(groebnerMatrix(2,0))); groebnerMatrix(31,39) = (groebnerMatrix(1,39)/(groebnerMatrix(1,0))-groebnerMatrix(2,39)/(groebnerMatrix(2,0))); groebnerMatrix(31,40) = (groebnerMatrix(1,40)/(groebnerMatrix(1,0))-groebnerMatrix(2,40)/(groebnerMatrix(2,0))); groebnerMatrix(31,41) = (groebnerMatrix(1,41)/(groebnerMatrix(1,0))-groebnerMatrix(2,41)/(groebnerMatrix(2,0))); groebnerMatrix(31,42) = (groebnerMatrix(1,42)/(groebnerMatrix(1,0))-groebnerMatrix(2,42)/(groebnerMatrix(2,0))); groebnerMatrix(31,43) = (groebnerMatrix(1,43)/(groebnerMatrix(1,0))-groebnerMatrix(2,43)/(groebnerMatrix(2,0))); groebnerMatrix(31,44) = (groebnerMatrix(1,44)/(groebnerMatrix(1,0))-groebnerMatrix(2,44)/(groebnerMatrix(2,0))); groebnerMatrix(31,45) = (groebnerMatrix(1,45)/(groebnerMatrix(1,0))-groebnerMatrix(2,45)/(groebnerMatrix(2,0))); groebnerMatrix(31,46) = (groebnerMatrix(1,46)/(groebnerMatrix(1,0))-groebnerMatrix(2,46)/(groebnerMatrix(2,0))); groebnerMatrix(31,47) = (groebnerMatrix(1,47)/(groebnerMatrix(1,0))-groebnerMatrix(2,47)/(groebnerMatrix(2,0))); groebnerMatrix(31,48) = (groebnerMatrix(1,48)/(groebnerMatrix(1,0))-groebnerMatrix(2,48)/(groebnerMatrix(2,0))); groebnerMatrix(31,49) = (groebnerMatrix(1,49)/(groebnerMatrix(1,0))-groebnerMatrix(2,49)/(groebnerMatrix(2,0))); groebnerMatrix(31,50) = (groebnerMatrix(1,50)/(groebnerMatrix(1,0))-groebnerMatrix(2,50)/(groebnerMatrix(2,0))); groebnerMatrix(31,51) = (groebnerMatrix(1,51)/(groebnerMatrix(1,0))-groebnerMatrix(2,51)/(groebnerMatrix(2,0))); groebnerMatrix(31,52) = (groebnerMatrix(1,52)/(groebnerMatrix(1,0))-groebnerMatrix(2,52)/(groebnerMatrix(2,0))); groebnerMatrix(31,53) = (groebnerMatrix(1,53)/(groebnerMatrix(1,0))-groebnerMatrix(2,53)/(groebnerMatrix(2,0))); groebnerMatrix(31,54) = (groebnerMatrix(1,54)/(groebnerMatrix(1,0))-groebnerMatrix(2,54)/(groebnerMatrix(2,0))); groebnerMatrix(31,55) = (groebnerMatrix(1,55)/(groebnerMatrix(1,0))-groebnerMatrix(2,55)/(groebnerMatrix(2,0))); groebnerMatrix(31,56) = (groebnerMatrix(1,56)/(groebnerMatrix(1,0))-groebnerMatrix(2,56)/(groebnerMatrix(2,0))); groebnerMatrix(31,57) = (groebnerMatrix(1,57)/(groebnerMatrix(1,0))-groebnerMatrix(2,57)/(groebnerMatrix(2,0))); groebnerMatrix(31,58) = (groebnerMatrix(1,58)/(groebnerMatrix(1,0))-groebnerMatrix(2,58)/(groebnerMatrix(2,0))); groebnerMatrix(31,59) = (groebnerMatrix(1,59)/(groebnerMatrix(1,0))-groebnerMatrix(2,59)/(groebnerMatrix(2,0))); groebnerMatrix(31,60) = (groebnerMatrix(1,60)/(groebnerMatrix(1,0))-groebnerMatrix(2,60)/(groebnerMatrix(2,0))); groebnerMatrix(31,61) = (groebnerMatrix(1,61)/(groebnerMatrix(1,0))-groebnerMatrix(2,61)/(groebnerMatrix(2,0))); groebnerMatrix(31,62) = (groebnerMatrix(1,62)/(groebnerMatrix(1,0))-groebnerMatrix(2,62)/(groebnerMatrix(2,0))); groebnerMatrix(31,64) = (groebnerMatrix(1,64)/(groebnerMatrix(1,0))-groebnerMatrix(2,64)/(groebnerMatrix(2,0))); groebnerMatrix(31,65) = (groebnerMatrix(1,65)/(groebnerMatrix(1,0))-groebnerMatrix(2,65)/(groebnerMatrix(2,0))); groebnerMatrix(31,66) = (groebnerMatrix(1,66)/(groebnerMatrix(1,0))-groebnerMatrix(2,66)/(groebnerMatrix(2,0))); groebnerMatrix(31,67) = (groebnerMatrix(1,67)/(groebnerMatrix(1,0))-groebnerMatrix(2,67)/(groebnerMatrix(2,0))); groebnerMatrix(31,68) = (groebnerMatrix(1,68)/(groebnerMatrix(1,0))-groebnerMatrix(2,68)/(groebnerMatrix(2,0))); groebnerMatrix(31,69) = (groebnerMatrix(1,69)/(groebnerMatrix(1,0))-groebnerMatrix(2,69)/(groebnerMatrix(2,0))); groebnerMatrix(31,70) = (groebnerMatrix(1,70)/(groebnerMatrix(1,0))-groebnerMatrix(2,70)/(groebnerMatrix(2,0))); groebnerMatrix(31,71) = (groebnerMatrix(1,71)/(groebnerMatrix(1,0))-groebnerMatrix(2,71)/(groebnerMatrix(2,0))); groebnerMatrix(31,73) = (groebnerMatrix(1,73)/(groebnerMatrix(1,0))-groebnerMatrix(2,73)/(groebnerMatrix(2,0))); groebnerMatrix(31,74) = (groebnerMatrix(1,74)/(groebnerMatrix(1,0))-groebnerMatrix(2,74)/(groebnerMatrix(2,0))); groebnerMatrix(31,76) = (groebnerMatrix(1,76)/(groebnerMatrix(1,0))-groebnerMatrix(2,76)/(groebnerMatrix(2,0))); groebnerMatrix(31,77) = (groebnerMatrix(1,77)/(groebnerMatrix(1,0))-groebnerMatrix(2,77)/(groebnerMatrix(2,0))); groebnerMatrix(31,78) = (groebnerMatrix(1,78)/(groebnerMatrix(1,0))-groebnerMatrix(2,78)/(groebnerMatrix(2,0))); groebnerMatrix(31,79) = (groebnerMatrix(1,79)/(groebnerMatrix(1,0))-groebnerMatrix(2,79)/(groebnerMatrix(2,0))); groebnerMatrix(31,80) = (groebnerMatrix(1,80)/(groebnerMatrix(1,0))-groebnerMatrix(2,80)/(groebnerMatrix(2,0))); groebnerMatrix(31,81) = (groebnerMatrix(1,81)/(groebnerMatrix(1,0))-groebnerMatrix(2,81)/(groebnerMatrix(2,0))); groebnerMatrix(31,82) = (groebnerMatrix(1,82)/(groebnerMatrix(1,0))-groebnerMatrix(2,82)/(groebnerMatrix(2,0))); groebnerMatrix(31,83) = (groebnerMatrix(1,83)/(groebnerMatrix(1,0))-groebnerMatrix(2,83)/(groebnerMatrix(2,0))); groebnerMatrix(31,84) = (groebnerMatrix(1,84)/(groebnerMatrix(1,0))-groebnerMatrix(2,84)/(groebnerMatrix(2,0))); groebnerMatrix(31,85) = (groebnerMatrix(1,85)/(groebnerMatrix(1,0))-groebnerMatrix(2,85)/(groebnerMatrix(2,0))); groebnerMatrix(31,86) = (groebnerMatrix(1,86)/(groebnerMatrix(1,0))-groebnerMatrix(2,86)/(groebnerMatrix(2,0))); groebnerMatrix(31,87) = (groebnerMatrix(1,87)/(groebnerMatrix(1,0))-groebnerMatrix(2,87)/(groebnerMatrix(2,0))); groebnerMatrix(31,89) = (groebnerMatrix(1,89)/(groebnerMatrix(1,0))-groebnerMatrix(2,89)/(groebnerMatrix(2,0))); groebnerMatrix(31,91) = (groebnerMatrix(1,91)/(groebnerMatrix(1,0))-groebnerMatrix(2,91)/(groebnerMatrix(2,0))); groebnerMatrix(31,92) = (groebnerMatrix(1,92)/(groebnerMatrix(1,0))-groebnerMatrix(2,92)/(groebnerMatrix(2,0))); groebnerMatrix(31,94) = (groebnerMatrix(1,94)/(groebnerMatrix(1,0))-groebnerMatrix(2,94)/(groebnerMatrix(2,0))); groebnerMatrix(31,97) = (groebnerMatrix(1,97)/(groebnerMatrix(1,0))-groebnerMatrix(2,97)/(groebnerMatrix(2,0))); groebnerMatrix(31,98) = (groebnerMatrix(1,98)/(groebnerMatrix(1,0))-groebnerMatrix(2,98)/(groebnerMatrix(2,0))); groebnerMatrix(31,99) = (groebnerMatrix(1,99)/(groebnerMatrix(1,0))-groebnerMatrix(2,99)/(groebnerMatrix(2,0))); groebnerMatrix(31,100) = (groebnerMatrix(1,100)/(groebnerMatrix(1,0))-groebnerMatrix(2,100)/(groebnerMatrix(2,0))); groebnerMatrix(31,101) = (groebnerMatrix(1,101)/(groebnerMatrix(1,0))-groebnerMatrix(2,101)/(groebnerMatrix(2,0))); groebnerMatrix(31,103) = (groebnerMatrix(1,103)/(groebnerMatrix(1,0))-groebnerMatrix(2,103)/(groebnerMatrix(2,0))); groebnerMatrix(31,104) = (groebnerMatrix(1,104)/(groebnerMatrix(1,0))-groebnerMatrix(2,104)/(groebnerMatrix(2,0))); groebnerMatrix(31,105) = (groebnerMatrix(1,105)/(groebnerMatrix(1,0))-groebnerMatrix(2,105)/(groebnerMatrix(2,0))); groebnerMatrix(31,106) = (groebnerMatrix(1,106)/(groebnerMatrix(1,0))-groebnerMatrix(2,106)/(groebnerMatrix(2,0))); groebnerMatrix(31,107) = (groebnerMatrix(1,107)/(groebnerMatrix(1,0))-groebnerMatrix(2,107)/(groebnerMatrix(2,0))); groebnerMatrix(31,108) = (groebnerMatrix(1,108)/(groebnerMatrix(1,0))-groebnerMatrix(2,108)/(groebnerMatrix(2,0))); groebnerMatrix(31,109) = (groebnerMatrix(1,109)/(groebnerMatrix(1,0))-groebnerMatrix(2,109)/(groebnerMatrix(2,0))); groebnerMatrix(31,110) = (groebnerMatrix(1,110)/(groebnerMatrix(1,0))-groebnerMatrix(2,110)/(groebnerMatrix(2,0))); groebnerMatrix(31,111) = (groebnerMatrix(1,111)/(groebnerMatrix(1,0))-groebnerMatrix(2,111)/(groebnerMatrix(2,0))); groebnerMatrix(31,112) = (groebnerMatrix(1,112)/(groebnerMatrix(1,0))-groebnerMatrix(2,112)/(groebnerMatrix(2,0))); groebnerMatrix(31,113) = (groebnerMatrix(1,113)/(groebnerMatrix(1,0))-groebnerMatrix(2,113)/(groebnerMatrix(2,0))); groebnerMatrix(31,115) = (groebnerMatrix(1,115)/(groebnerMatrix(1,0))-groebnerMatrix(2,115)/(groebnerMatrix(2,0))); groebnerMatrix(31,116) = (groebnerMatrix(1,116)/(groebnerMatrix(1,0))-groebnerMatrix(2,116)/(groebnerMatrix(2,0))); groebnerMatrix(31,118) = (groebnerMatrix(1,118)/(groebnerMatrix(1,0))-groebnerMatrix(2,118)/(groebnerMatrix(2,0))); groebnerMatrix(31,119) = (groebnerMatrix(1,119)/(groebnerMatrix(1,0))-groebnerMatrix(2,119)/(groebnerMatrix(2,0))); groebnerMatrix(31,120) = (groebnerMatrix(1,120)/(groebnerMatrix(1,0))-groebnerMatrix(2,120)/(groebnerMatrix(2,0))); groebnerMatrix(31,121) = (groebnerMatrix(1,121)/(groebnerMatrix(1,0))-groebnerMatrix(2,121)/(groebnerMatrix(2,0))); groebnerMatrix(31,122) = (groebnerMatrix(1,122)/(groebnerMatrix(1,0))-groebnerMatrix(2,122)/(groebnerMatrix(2,0))); groebnerMatrix(31,123) = (groebnerMatrix(1,123)/(groebnerMatrix(1,0))-groebnerMatrix(2,123)/(groebnerMatrix(2,0))); groebnerMatrix(31,125) = (groebnerMatrix(1,125)/(groebnerMatrix(1,0))-groebnerMatrix(2,125)/(groebnerMatrix(2,0))); groebnerMatrix(31,126) = (groebnerMatrix(1,126)/(groebnerMatrix(1,0))-groebnerMatrix(2,126)/(groebnerMatrix(2,0))); groebnerMatrix(31,127) = (groebnerMatrix(1,127)/(groebnerMatrix(1,0))-groebnerMatrix(2,127)/(groebnerMatrix(2,0))); groebnerMatrix(31,128) = (groebnerMatrix(1,128)/(groebnerMatrix(1,0))-groebnerMatrix(2,128)/(groebnerMatrix(2,0))); groebnerMatrix(31,129) = (groebnerMatrix(1,129)/(groebnerMatrix(1,0))-groebnerMatrix(2,129)/(groebnerMatrix(2,0))); groebnerMatrix(31,130) = (groebnerMatrix(1,130)/(groebnerMatrix(1,0))-groebnerMatrix(2,130)/(groebnerMatrix(2,0))); groebnerMatrix(31,133) = (groebnerMatrix(1,133)/(groebnerMatrix(1,0))-groebnerMatrix(2,133)/(groebnerMatrix(2,0))); groebnerMatrix(31,134) = (groebnerMatrix(1,134)/(groebnerMatrix(1,0))-groebnerMatrix(2,134)/(groebnerMatrix(2,0))); groebnerMatrix(31,136) = (groebnerMatrix(1,136)/(groebnerMatrix(1,0))-groebnerMatrix(2,136)/(groebnerMatrix(2,0))); groebnerMatrix(31,137) = (groebnerMatrix(1,137)/(groebnerMatrix(1,0))-groebnerMatrix(2,137)/(groebnerMatrix(2,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial32( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(32,1) = (groebnerMatrix(2,1)/(groebnerMatrix(2,0))-groebnerMatrix(3,1)/(groebnerMatrix(3,0))); groebnerMatrix(32,2) = (groebnerMatrix(2,2)/(groebnerMatrix(2,0))-groebnerMatrix(3,2)/(groebnerMatrix(3,0))); groebnerMatrix(32,3) = (groebnerMatrix(2,3)/(groebnerMatrix(2,0))-groebnerMatrix(3,3)/(groebnerMatrix(3,0))); groebnerMatrix(32,4) = (groebnerMatrix(2,4)/(groebnerMatrix(2,0))-groebnerMatrix(3,4)/(groebnerMatrix(3,0))); groebnerMatrix(32,5) = (groebnerMatrix(2,5)/(groebnerMatrix(2,0))-groebnerMatrix(3,5)/(groebnerMatrix(3,0))); groebnerMatrix(32,6) = (groebnerMatrix(2,6)/(groebnerMatrix(2,0))-groebnerMatrix(3,6)/(groebnerMatrix(3,0))); groebnerMatrix(32,8) = (groebnerMatrix(2,8)/(groebnerMatrix(2,0))-groebnerMatrix(3,8)/(groebnerMatrix(3,0))); groebnerMatrix(32,10) = (groebnerMatrix(2,10)/(groebnerMatrix(2,0))-groebnerMatrix(3,10)/(groebnerMatrix(3,0))); groebnerMatrix(32,11) = (groebnerMatrix(2,11)/(groebnerMatrix(2,0))-groebnerMatrix(3,11)/(groebnerMatrix(3,0))); groebnerMatrix(32,12) = (groebnerMatrix(2,12)/(groebnerMatrix(2,0))-groebnerMatrix(3,12)/(groebnerMatrix(3,0))); groebnerMatrix(32,13) = (groebnerMatrix(2,13)/(groebnerMatrix(2,0))-groebnerMatrix(3,13)/(groebnerMatrix(3,0))); groebnerMatrix(32,14) = (groebnerMatrix(2,14)/(groebnerMatrix(2,0))-groebnerMatrix(3,14)/(groebnerMatrix(3,0))); groebnerMatrix(32,15) = (groebnerMatrix(2,15)/(groebnerMatrix(2,0))-groebnerMatrix(3,15)/(groebnerMatrix(3,0))); groebnerMatrix(32,16) = (groebnerMatrix(2,16)/(groebnerMatrix(2,0))-groebnerMatrix(3,16)/(groebnerMatrix(3,0))); groebnerMatrix(32,18) = (groebnerMatrix(2,18)/(groebnerMatrix(2,0))-groebnerMatrix(3,18)/(groebnerMatrix(3,0))); groebnerMatrix(32,19) = (groebnerMatrix(2,19)/(groebnerMatrix(2,0))-groebnerMatrix(3,19)/(groebnerMatrix(3,0))); groebnerMatrix(32,20) = (groebnerMatrix(2,20)/(groebnerMatrix(2,0))-groebnerMatrix(3,20)/(groebnerMatrix(3,0))); groebnerMatrix(32,21) = (groebnerMatrix(2,21)/(groebnerMatrix(2,0))-groebnerMatrix(3,21)/(groebnerMatrix(3,0))); groebnerMatrix(32,22) = (groebnerMatrix(2,22)/(groebnerMatrix(2,0))-groebnerMatrix(3,22)/(groebnerMatrix(3,0))); groebnerMatrix(32,23) = (groebnerMatrix(2,23)/(groebnerMatrix(2,0))-groebnerMatrix(3,23)/(groebnerMatrix(3,0))); groebnerMatrix(32,25) = (groebnerMatrix(2,25)/(groebnerMatrix(2,0))-groebnerMatrix(3,25)/(groebnerMatrix(3,0))); groebnerMatrix(32,26) = (groebnerMatrix(2,26)/(groebnerMatrix(2,0))-groebnerMatrix(3,26)/(groebnerMatrix(3,0))); groebnerMatrix(32,27) = (groebnerMatrix(2,27)/(groebnerMatrix(2,0))-groebnerMatrix(3,27)/(groebnerMatrix(3,0))); groebnerMatrix(32,28) = (groebnerMatrix(2,28)/(groebnerMatrix(2,0))-groebnerMatrix(3,28)/(groebnerMatrix(3,0))); groebnerMatrix(32,29) = (groebnerMatrix(2,29)/(groebnerMatrix(2,0))-groebnerMatrix(3,29)/(groebnerMatrix(3,0))); groebnerMatrix(32,30) = (groebnerMatrix(2,30)/(groebnerMatrix(2,0))-groebnerMatrix(3,30)/(groebnerMatrix(3,0))); groebnerMatrix(32,33) = (groebnerMatrix(2,33)/(groebnerMatrix(2,0))-groebnerMatrix(3,33)/(groebnerMatrix(3,0))); groebnerMatrix(32,34) = (groebnerMatrix(2,34)/(groebnerMatrix(2,0))-groebnerMatrix(3,34)/(groebnerMatrix(3,0))); groebnerMatrix(32,39) = (groebnerMatrix(2,39)/(groebnerMatrix(2,0))-groebnerMatrix(3,39)/(groebnerMatrix(3,0))); groebnerMatrix(32,40) = (groebnerMatrix(2,40)/(groebnerMatrix(2,0))-groebnerMatrix(3,40)/(groebnerMatrix(3,0))); groebnerMatrix(32,41) = (groebnerMatrix(2,41)/(groebnerMatrix(2,0))-groebnerMatrix(3,41)/(groebnerMatrix(3,0))); groebnerMatrix(32,42) = (groebnerMatrix(2,42)/(groebnerMatrix(2,0))-groebnerMatrix(3,42)/(groebnerMatrix(3,0))); groebnerMatrix(32,43) = (groebnerMatrix(2,43)/(groebnerMatrix(2,0))-groebnerMatrix(3,43)/(groebnerMatrix(3,0))); groebnerMatrix(32,44) = (groebnerMatrix(2,44)/(groebnerMatrix(2,0))-groebnerMatrix(3,44)/(groebnerMatrix(3,0))); groebnerMatrix(32,45) = (groebnerMatrix(2,45)/(groebnerMatrix(2,0))-groebnerMatrix(3,45)/(groebnerMatrix(3,0))); groebnerMatrix(32,46) = (groebnerMatrix(2,46)/(groebnerMatrix(2,0))-groebnerMatrix(3,46)/(groebnerMatrix(3,0))); groebnerMatrix(32,47) = (groebnerMatrix(2,47)/(groebnerMatrix(2,0))-groebnerMatrix(3,47)/(groebnerMatrix(3,0))); groebnerMatrix(32,48) = (groebnerMatrix(2,48)/(groebnerMatrix(2,0))-groebnerMatrix(3,48)/(groebnerMatrix(3,0))); groebnerMatrix(32,49) = (groebnerMatrix(2,49)/(groebnerMatrix(2,0))-groebnerMatrix(3,49)/(groebnerMatrix(3,0))); groebnerMatrix(32,50) = (groebnerMatrix(2,50)/(groebnerMatrix(2,0))-groebnerMatrix(3,50)/(groebnerMatrix(3,0))); groebnerMatrix(32,51) = (groebnerMatrix(2,51)/(groebnerMatrix(2,0))-groebnerMatrix(3,51)/(groebnerMatrix(3,0))); groebnerMatrix(32,52) = (groebnerMatrix(2,52)/(groebnerMatrix(2,0))-groebnerMatrix(3,52)/(groebnerMatrix(3,0))); groebnerMatrix(32,53) = (groebnerMatrix(2,53)/(groebnerMatrix(2,0))-groebnerMatrix(3,53)/(groebnerMatrix(3,0))); groebnerMatrix(32,54) = (groebnerMatrix(2,54)/(groebnerMatrix(2,0))-groebnerMatrix(3,54)/(groebnerMatrix(3,0))); groebnerMatrix(32,55) = (groebnerMatrix(2,55)/(groebnerMatrix(2,0))-groebnerMatrix(3,55)/(groebnerMatrix(3,0))); groebnerMatrix(32,56) = (groebnerMatrix(2,56)/(groebnerMatrix(2,0))-groebnerMatrix(3,56)/(groebnerMatrix(3,0))); groebnerMatrix(32,57) = (groebnerMatrix(2,57)/(groebnerMatrix(2,0))-groebnerMatrix(3,57)/(groebnerMatrix(3,0))); groebnerMatrix(32,58) = (groebnerMatrix(2,58)/(groebnerMatrix(2,0))-groebnerMatrix(3,58)/(groebnerMatrix(3,0))); groebnerMatrix(32,59) = (groebnerMatrix(2,59)/(groebnerMatrix(2,0))-groebnerMatrix(3,59)/(groebnerMatrix(3,0))); groebnerMatrix(32,60) = (groebnerMatrix(2,60)/(groebnerMatrix(2,0))-groebnerMatrix(3,60)/(groebnerMatrix(3,0))); groebnerMatrix(32,61) = (groebnerMatrix(2,61)/(groebnerMatrix(2,0))-groebnerMatrix(3,61)/(groebnerMatrix(3,0))); groebnerMatrix(32,62) = (groebnerMatrix(2,62)/(groebnerMatrix(2,0))-groebnerMatrix(3,62)/(groebnerMatrix(3,0))); groebnerMatrix(32,64) = (groebnerMatrix(2,64)/(groebnerMatrix(2,0))-groebnerMatrix(3,64)/(groebnerMatrix(3,0))); groebnerMatrix(32,65) = (groebnerMatrix(2,65)/(groebnerMatrix(2,0))-groebnerMatrix(3,65)/(groebnerMatrix(3,0))); groebnerMatrix(32,66) = (groebnerMatrix(2,66)/(groebnerMatrix(2,0))-groebnerMatrix(3,66)/(groebnerMatrix(3,0))); groebnerMatrix(32,67) = (groebnerMatrix(2,67)/(groebnerMatrix(2,0))-groebnerMatrix(3,67)/(groebnerMatrix(3,0))); groebnerMatrix(32,68) = (groebnerMatrix(2,68)/(groebnerMatrix(2,0))-groebnerMatrix(3,68)/(groebnerMatrix(3,0))); groebnerMatrix(32,69) = (groebnerMatrix(2,69)/(groebnerMatrix(2,0))-groebnerMatrix(3,69)/(groebnerMatrix(3,0))); groebnerMatrix(32,70) = (groebnerMatrix(2,70)/(groebnerMatrix(2,0))-groebnerMatrix(3,70)/(groebnerMatrix(3,0))); groebnerMatrix(32,71) = (groebnerMatrix(2,71)/(groebnerMatrix(2,0))-groebnerMatrix(3,71)/(groebnerMatrix(3,0))); groebnerMatrix(32,73) = (groebnerMatrix(2,73)/(groebnerMatrix(2,0))-groebnerMatrix(3,73)/(groebnerMatrix(3,0))); groebnerMatrix(32,74) = (groebnerMatrix(2,74)/(groebnerMatrix(2,0))-groebnerMatrix(3,74)/(groebnerMatrix(3,0))); groebnerMatrix(32,76) = (groebnerMatrix(2,76)/(groebnerMatrix(2,0))-groebnerMatrix(3,76)/(groebnerMatrix(3,0))); groebnerMatrix(32,77) = (groebnerMatrix(2,77)/(groebnerMatrix(2,0))-groebnerMatrix(3,77)/(groebnerMatrix(3,0))); groebnerMatrix(32,78) = (groebnerMatrix(2,78)/(groebnerMatrix(2,0))-groebnerMatrix(3,78)/(groebnerMatrix(3,0))); groebnerMatrix(32,79) = (groebnerMatrix(2,79)/(groebnerMatrix(2,0))-groebnerMatrix(3,79)/(groebnerMatrix(3,0))); groebnerMatrix(32,80) = (groebnerMatrix(2,80)/(groebnerMatrix(2,0))-groebnerMatrix(3,80)/(groebnerMatrix(3,0))); groebnerMatrix(32,81) = (groebnerMatrix(2,81)/(groebnerMatrix(2,0))-groebnerMatrix(3,81)/(groebnerMatrix(3,0))); groebnerMatrix(32,82) = (groebnerMatrix(2,82)/(groebnerMatrix(2,0))-groebnerMatrix(3,82)/(groebnerMatrix(3,0))); groebnerMatrix(32,83) = (groebnerMatrix(2,83)/(groebnerMatrix(2,0))-groebnerMatrix(3,83)/(groebnerMatrix(3,0))); groebnerMatrix(32,84) = (groebnerMatrix(2,84)/(groebnerMatrix(2,0))-groebnerMatrix(3,84)/(groebnerMatrix(3,0))); groebnerMatrix(32,85) = (groebnerMatrix(2,85)/(groebnerMatrix(2,0))-groebnerMatrix(3,85)/(groebnerMatrix(3,0))); groebnerMatrix(32,86) = (groebnerMatrix(2,86)/(groebnerMatrix(2,0))-groebnerMatrix(3,86)/(groebnerMatrix(3,0))); groebnerMatrix(32,87) = (groebnerMatrix(2,87)/(groebnerMatrix(2,0))-groebnerMatrix(3,87)/(groebnerMatrix(3,0))); groebnerMatrix(32,89) = (groebnerMatrix(2,89)/(groebnerMatrix(2,0))-groebnerMatrix(3,89)/(groebnerMatrix(3,0))); groebnerMatrix(32,91) = (groebnerMatrix(2,91)/(groebnerMatrix(2,0))-groebnerMatrix(3,91)/(groebnerMatrix(3,0))); groebnerMatrix(32,92) = (groebnerMatrix(2,92)/(groebnerMatrix(2,0))-groebnerMatrix(3,92)/(groebnerMatrix(3,0))); groebnerMatrix(32,94) = (groebnerMatrix(2,94)/(groebnerMatrix(2,0))-groebnerMatrix(3,94)/(groebnerMatrix(3,0))); groebnerMatrix(32,97) = (groebnerMatrix(2,97)/(groebnerMatrix(2,0))-groebnerMatrix(3,97)/(groebnerMatrix(3,0))); groebnerMatrix(32,98) = (groebnerMatrix(2,98)/(groebnerMatrix(2,0))-groebnerMatrix(3,98)/(groebnerMatrix(3,0))); groebnerMatrix(32,99) = (groebnerMatrix(2,99)/(groebnerMatrix(2,0))-groebnerMatrix(3,99)/(groebnerMatrix(3,0))); groebnerMatrix(32,100) = (groebnerMatrix(2,100)/(groebnerMatrix(2,0))-groebnerMatrix(3,100)/(groebnerMatrix(3,0))); groebnerMatrix(32,101) = (groebnerMatrix(2,101)/(groebnerMatrix(2,0))-groebnerMatrix(3,101)/(groebnerMatrix(3,0))); groebnerMatrix(32,103) = (groebnerMatrix(2,103)/(groebnerMatrix(2,0))-groebnerMatrix(3,103)/(groebnerMatrix(3,0))); groebnerMatrix(32,104) = (groebnerMatrix(2,104)/(groebnerMatrix(2,0))-groebnerMatrix(3,104)/(groebnerMatrix(3,0))); groebnerMatrix(32,105) = (groebnerMatrix(2,105)/(groebnerMatrix(2,0))-groebnerMatrix(3,105)/(groebnerMatrix(3,0))); groebnerMatrix(32,106) = (groebnerMatrix(2,106)/(groebnerMatrix(2,0))-groebnerMatrix(3,106)/(groebnerMatrix(3,0))); groebnerMatrix(32,107) = (groebnerMatrix(2,107)/(groebnerMatrix(2,0))-groebnerMatrix(3,107)/(groebnerMatrix(3,0))); groebnerMatrix(32,108) = (groebnerMatrix(2,108)/(groebnerMatrix(2,0))-groebnerMatrix(3,108)/(groebnerMatrix(3,0))); groebnerMatrix(32,109) = (groebnerMatrix(2,109)/(groebnerMatrix(2,0))-groebnerMatrix(3,109)/(groebnerMatrix(3,0))); groebnerMatrix(32,110) = (groebnerMatrix(2,110)/(groebnerMatrix(2,0))-groebnerMatrix(3,110)/(groebnerMatrix(3,0))); groebnerMatrix(32,111) = (groebnerMatrix(2,111)/(groebnerMatrix(2,0))-groebnerMatrix(3,111)/(groebnerMatrix(3,0))); groebnerMatrix(32,112) = (groebnerMatrix(2,112)/(groebnerMatrix(2,0))-groebnerMatrix(3,112)/(groebnerMatrix(3,0))); groebnerMatrix(32,113) = (groebnerMatrix(2,113)/(groebnerMatrix(2,0))-groebnerMatrix(3,113)/(groebnerMatrix(3,0))); groebnerMatrix(32,115) = (groebnerMatrix(2,115)/(groebnerMatrix(2,0))-groebnerMatrix(3,115)/(groebnerMatrix(3,0))); groebnerMatrix(32,116) = (groebnerMatrix(2,116)/(groebnerMatrix(2,0))-groebnerMatrix(3,116)/(groebnerMatrix(3,0))); groebnerMatrix(32,118) = (groebnerMatrix(2,118)/(groebnerMatrix(2,0))-groebnerMatrix(3,118)/(groebnerMatrix(3,0))); groebnerMatrix(32,119) = (groebnerMatrix(2,119)/(groebnerMatrix(2,0))-groebnerMatrix(3,119)/(groebnerMatrix(3,0))); groebnerMatrix(32,120) = (groebnerMatrix(2,120)/(groebnerMatrix(2,0))-groebnerMatrix(3,120)/(groebnerMatrix(3,0))); groebnerMatrix(32,121) = (groebnerMatrix(2,121)/(groebnerMatrix(2,0))-groebnerMatrix(3,121)/(groebnerMatrix(3,0))); groebnerMatrix(32,122) = (groebnerMatrix(2,122)/(groebnerMatrix(2,0))-groebnerMatrix(3,122)/(groebnerMatrix(3,0))); groebnerMatrix(32,123) = (groebnerMatrix(2,123)/(groebnerMatrix(2,0))-groebnerMatrix(3,123)/(groebnerMatrix(3,0))); groebnerMatrix(32,125) = (groebnerMatrix(2,125)/(groebnerMatrix(2,0))-groebnerMatrix(3,125)/(groebnerMatrix(3,0))); groebnerMatrix(32,126) = (groebnerMatrix(2,126)/(groebnerMatrix(2,0))-groebnerMatrix(3,126)/(groebnerMatrix(3,0))); groebnerMatrix(32,127) = (groebnerMatrix(2,127)/(groebnerMatrix(2,0))-groebnerMatrix(3,127)/(groebnerMatrix(3,0))); groebnerMatrix(32,128) = (groebnerMatrix(2,128)/(groebnerMatrix(2,0))-groebnerMatrix(3,128)/(groebnerMatrix(3,0))); groebnerMatrix(32,129) = (groebnerMatrix(2,129)/(groebnerMatrix(2,0))-groebnerMatrix(3,129)/(groebnerMatrix(3,0))); groebnerMatrix(32,130) = (groebnerMatrix(2,130)/(groebnerMatrix(2,0))-groebnerMatrix(3,130)/(groebnerMatrix(3,0))); groebnerMatrix(32,133) = (groebnerMatrix(2,133)/(groebnerMatrix(2,0))-groebnerMatrix(3,133)/(groebnerMatrix(3,0))); groebnerMatrix(32,134) = (groebnerMatrix(2,134)/(groebnerMatrix(2,0))-groebnerMatrix(3,134)/(groebnerMatrix(3,0))); groebnerMatrix(32,136) = (groebnerMatrix(2,136)/(groebnerMatrix(2,0))-groebnerMatrix(3,136)/(groebnerMatrix(3,0))); groebnerMatrix(32,137) = (groebnerMatrix(2,137)/(groebnerMatrix(2,0))-groebnerMatrix(3,137)/(groebnerMatrix(3,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial33( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(33,1) = (groebnerMatrix(3,1)/(groebnerMatrix(3,0))-groebnerMatrix(4,1)/(groebnerMatrix(4,0))); groebnerMatrix(33,2) = (groebnerMatrix(3,2)/(groebnerMatrix(3,0))-groebnerMatrix(4,2)/(groebnerMatrix(4,0))); groebnerMatrix(33,3) = (groebnerMatrix(3,3)/(groebnerMatrix(3,0))-groebnerMatrix(4,3)/(groebnerMatrix(4,0))); groebnerMatrix(33,4) = (groebnerMatrix(3,4)/(groebnerMatrix(3,0))-groebnerMatrix(4,4)/(groebnerMatrix(4,0))); groebnerMatrix(33,5) = (groebnerMatrix(3,5)/(groebnerMatrix(3,0))-groebnerMatrix(4,5)/(groebnerMatrix(4,0))); groebnerMatrix(33,6) = (groebnerMatrix(3,6)/(groebnerMatrix(3,0))-groebnerMatrix(4,6)/(groebnerMatrix(4,0))); groebnerMatrix(33,8) = (groebnerMatrix(3,8)/(groebnerMatrix(3,0))-groebnerMatrix(4,8)/(groebnerMatrix(4,0))); groebnerMatrix(33,10) = (groebnerMatrix(3,10)/(groebnerMatrix(3,0))-groebnerMatrix(4,10)/(groebnerMatrix(4,0))); groebnerMatrix(33,11) = (groebnerMatrix(3,11)/(groebnerMatrix(3,0))-groebnerMatrix(4,11)/(groebnerMatrix(4,0))); groebnerMatrix(33,12) = (groebnerMatrix(3,12)/(groebnerMatrix(3,0))-groebnerMatrix(4,12)/(groebnerMatrix(4,0))); groebnerMatrix(33,13) = (groebnerMatrix(3,13)/(groebnerMatrix(3,0))-groebnerMatrix(4,13)/(groebnerMatrix(4,0))); groebnerMatrix(33,14) = (groebnerMatrix(3,14)/(groebnerMatrix(3,0))-groebnerMatrix(4,14)/(groebnerMatrix(4,0))); groebnerMatrix(33,15) = (groebnerMatrix(3,15)/(groebnerMatrix(3,0))-groebnerMatrix(4,15)/(groebnerMatrix(4,0))); groebnerMatrix(33,16) = (groebnerMatrix(3,16)/(groebnerMatrix(3,0))-groebnerMatrix(4,16)/(groebnerMatrix(4,0))); groebnerMatrix(33,18) = (groebnerMatrix(3,18)/(groebnerMatrix(3,0))-groebnerMatrix(4,18)/(groebnerMatrix(4,0))); groebnerMatrix(33,19) = (groebnerMatrix(3,19)/(groebnerMatrix(3,0))-groebnerMatrix(4,19)/(groebnerMatrix(4,0))); groebnerMatrix(33,20) = (groebnerMatrix(3,20)/(groebnerMatrix(3,0))-groebnerMatrix(4,20)/(groebnerMatrix(4,0))); groebnerMatrix(33,21) = (groebnerMatrix(3,21)/(groebnerMatrix(3,0))-groebnerMatrix(4,21)/(groebnerMatrix(4,0))); groebnerMatrix(33,22) = (groebnerMatrix(3,22)/(groebnerMatrix(3,0))-groebnerMatrix(4,22)/(groebnerMatrix(4,0))); groebnerMatrix(33,23) = (groebnerMatrix(3,23)/(groebnerMatrix(3,0))-groebnerMatrix(4,23)/(groebnerMatrix(4,0))); groebnerMatrix(33,25) = (groebnerMatrix(3,25)/(groebnerMatrix(3,0))-groebnerMatrix(4,25)/(groebnerMatrix(4,0))); groebnerMatrix(33,26) = (groebnerMatrix(3,26)/(groebnerMatrix(3,0))-groebnerMatrix(4,26)/(groebnerMatrix(4,0))); groebnerMatrix(33,27) = (groebnerMatrix(3,27)/(groebnerMatrix(3,0))-groebnerMatrix(4,27)/(groebnerMatrix(4,0))); groebnerMatrix(33,28) = (groebnerMatrix(3,28)/(groebnerMatrix(3,0))-groebnerMatrix(4,28)/(groebnerMatrix(4,0))); groebnerMatrix(33,29) = (groebnerMatrix(3,29)/(groebnerMatrix(3,0))-groebnerMatrix(4,29)/(groebnerMatrix(4,0))); groebnerMatrix(33,30) = (groebnerMatrix(3,30)/(groebnerMatrix(3,0))-groebnerMatrix(4,30)/(groebnerMatrix(4,0))); groebnerMatrix(33,33) = (groebnerMatrix(3,33)/(groebnerMatrix(3,0))-groebnerMatrix(4,33)/(groebnerMatrix(4,0))); groebnerMatrix(33,34) = (groebnerMatrix(3,34)/(groebnerMatrix(3,0))-groebnerMatrix(4,34)/(groebnerMatrix(4,0))); groebnerMatrix(33,39) = (groebnerMatrix(3,39)/(groebnerMatrix(3,0))-groebnerMatrix(4,39)/(groebnerMatrix(4,0))); groebnerMatrix(33,40) = (groebnerMatrix(3,40)/(groebnerMatrix(3,0))-groebnerMatrix(4,40)/(groebnerMatrix(4,0))); groebnerMatrix(33,41) = (groebnerMatrix(3,41)/(groebnerMatrix(3,0))-groebnerMatrix(4,41)/(groebnerMatrix(4,0))); groebnerMatrix(33,42) = (groebnerMatrix(3,42)/(groebnerMatrix(3,0))-groebnerMatrix(4,42)/(groebnerMatrix(4,0))); groebnerMatrix(33,43) = (groebnerMatrix(3,43)/(groebnerMatrix(3,0))-groebnerMatrix(4,43)/(groebnerMatrix(4,0))); groebnerMatrix(33,44) = (groebnerMatrix(3,44)/(groebnerMatrix(3,0))-groebnerMatrix(4,44)/(groebnerMatrix(4,0))); groebnerMatrix(33,45) = (groebnerMatrix(3,45)/(groebnerMatrix(3,0))-groebnerMatrix(4,45)/(groebnerMatrix(4,0))); groebnerMatrix(33,46) = (groebnerMatrix(3,46)/(groebnerMatrix(3,0))-groebnerMatrix(4,46)/(groebnerMatrix(4,0))); groebnerMatrix(33,47) = (groebnerMatrix(3,47)/(groebnerMatrix(3,0))-groebnerMatrix(4,47)/(groebnerMatrix(4,0))); groebnerMatrix(33,48) = (groebnerMatrix(3,48)/(groebnerMatrix(3,0))-groebnerMatrix(4,48)/(groebnerMatrix(4,0))); groebnerMatrix(33,49) = (groebnerMatrix(3,49)/(groebnerMatrix(3,0))-groebnerMatrix(4,49)/(groebnerMatrix(4,0))); groebnerMatrix(33,50) = (groebnerMatrix(3,50)/(groebnerMatrix(3,0))-groebnerMatrix(4,50)/(groebnerMatrix(4,0))); groebnerMatrix(33,51) = (groebnerMatrix(3,51)/(groebnerMatrix(3,0))-groebnerMatrix(4,51)/(groebnerMatrix(4,0))); groebnerMatrix(33,52) = (groebnerMatrix(3,52)/(groebnerMatrix(3,0))-groebnerMatrix(4,52)/(groebnerMatrix(4,0))); groebnerMatrix(33,53) = (groebnerMatrix(3,53)/(groebnerMatrix(3,0))-groebnerMatrix(4,53)/(groebnerMatrix(4,0))); groebnerMatrix(33,54) = (groebnerMatrix(3,54)/(groebnerMatrix(3,0))-groebnerMatrix(4,54)/(groebnerMatrix(4,0))); groebnerMatrix(33,55) = (groebnerMatrix(3,55)/(groebnerMatrix(3,0))-groebnerMatrix(4,55)/(groebnerMatrix(4,0))); groebnerMatrix(33,56) = (groebnerMatrix(3,56)/(groebnerMatrix(3,0))-groebnerMatrix(4,56)/(groebnerMatrix(4,0))); groebnerMatrix(33,57) = (groebnerMatrix(3,57)/(groebnerMatrix(3,0))-groebnerMatrix(4,57)/(groebnerMatrix(4,0))); groebnerMatrix(33,58) = (groebnerMatrix(3,58)/(groebnerMatrix(3,0))-groebnerMatrix(4,58)/(groebnerMatrix(4,0))); groebnerMatrix(33,59) = (groebnerMatrix(3,59)/(groebnerMatrix(3,0))-groebnerMatrix(4,59)/(groebnerMatrix(4,0))); groebnerMatrix(33,60) = (groebnerMatrix(3,60)/(groebnerMatrix(3,0))-groebnerMatrix(4,60)/(groebnerMatrix(4,0))); groebnerMatrix(33,61) = (groebnerMatrix(3,61)/(groebnerMatrix(3,0))-groebnerMatrix(4,61)/(groebnerMatrix(4,0))); groebnerMatrix(33,62) = (groebnerMatrix(3,62)/(groebnerMatrix(3,0))-groebnerMatrix(4,62)/(groebnerMatrix(4,0))); groebnerMatrix(33,64) = (groebnerMatrix(3,64)/(groebnerMatrix(3,0))-groebnerMatrix(4,64)/(groebnerMatrix(4,0))); groebnerMatrix(33,65) = (groebnerMatrix(3,65)/(groebnerMatrix(3,0))-groebnerMatrix(4,65)/(groebnerMatrix(4,0))); groebnerMatrix(33,66) = (groebnerMatrix(3,66)/(groebnerMatrix(3,0))-groebnerMatrix(4,66)/(groebnerMatrix(4,0))); groebnerMatrix(33,67) = (groebnerMatrix(3,67)/(groebnerMatrix(3,0))-groebnerMatrix(4,67)/(groebnerMatrix(4,0))); groebnerMatrix(33,68) = (groebnerMatrix(3,68)/(groebnerMatrix(3,0))-groebnerMatrix(4,68)/(groebnerMatrix(4,0))); groebnerMatrix(33,69) = (groebnerMatrix(3,69)/(groebnerMatrix(3,0))-groebnerMatrix(4,69)/(groebnerMatrix(4,0))); groebnerMatrix(33,70) = (groebnerMatrix(3,70)/(groebnerMatrix(3,0))-groebnerMatrix(4,70)/(groebnerMatrix(4,0))); groebnerMatrix(33,71) = (groebnerMatrix(3,71)/(groebnerMatrix(3,0))-groebnerMatrix(4,71)/(groebnerMatrix(4,0))); groebnerMatrix(33,73) = (groebnerMatrix(3,73)/(groebnerMatrix(3,0))-groebnerMatrix(4,73)/(groebnerMatrix(4,0))); groebnerMatrix(33,74) = (groebnerMatrix(3,74)/(groebnerMatrix(3,0))-groebnerMatrix(4,74)/(groebnerMatrix(4,0))); groebnerMatrix(33,76) = (groebnerMatrix(3,76)/(groebnerMatrix(3,0))-groebnerMatrix(4,76)/(groebnerMatrix(4,0))); groebnerMatrix(33,77) = (groebnerMatrix(3,77)/(groebnerMatrix(3,0))-groebnerMatrix(4,77)/(groebnerMatrix(4,0))); groebnerMatrix(33,78) = (groebnerMatrix(3,78)/(groebnerMatrix(3,0))-groebnerMatrix(4,78)/(groebnerMatrix(4,0))); groebnerMatrix(33,79) = (groebnerMatrix(3,79)/(groebnerMatrix(3,0))-groebnerMatrix(4,79)/(groebnerMatrix(4,0))); groebnerMatrix(33,80) = (groebnerMatrix(3,80)/(groebnerMatrix(3,0))-groebnerMatrix(4,80)/(groebnerMatrix(4,0))); groebnerMatrix(33,81) = (groebnerMatrix(3,81)/(groebnerMatrix(3,0))-groebnerMatrix(4,81)/(groebnerMatrix(4,0))); groebnerMatrix(33,82) = (groebnerMatrix(3,82)/(groebnerMatrix(3,0))-groebnerMatrix(4,82)/(groebnerMatrix(4,0))); groebnerMatrix(33,83) = (groebnerMatrix(3,83)/(groebnerMatrix(3,0))-groebnerMatrix(4,83)/(groebnerMatrix(4,0))); groebnerMatrix(33,84) = (groebnerMatrix(3,84)/(groebnerMatrix(3,0))-groebnerMatrix(4,84)/(groebnerMatrix(4,0))); groebnerMatrix(33,85) = (groebnerMatrix(3,85)/(groebnerMatrix(3,0))-groebnerMatrix(4,85)/(groebnerMatrix(4,0))); groebnerMatrix(33,86) = (groebnerMatrix(3,86)/(groebnerMatrix(3,0))-groebnerMatrix(4,86)/(groebnerMatrix(4,0))); groebnerMatrix(33,87) = (groebnerMatrix(3,87)/(groebnerMatrix(3,0))-groebnerMatrix(4,87)/(groebnerMatrix(4,0))); groebnerMatrix(33,89) = (groebnerMatrix(3,89)/(groebnerMatrix(3,0))-groebnerMatrix(4,89)/(groebnerMatrix(4,0))); groebnerMatrix(33,91) = (groebnerMatrix(3,91)/(groebnerMatrix(3,0))-groebnerMatrix(4,91)/(groebnerMatrix(4,0))); groebnerMatrix(33,92) = (groebnerMatrix(3,92)/(groebnerMatrix(3,0))-groebnerMatrix(4,92)/(groebnerMatrix(4,0))); groebnerMatrix(33,94) = (groebnerMatrix(3,94)/(groebnerMatrix(3,0))-groebnerMatrix(4,94)/(groebnerMatrix(4,0))); groebnerMatrix(33,97) = (groebnerMatrix(3,97)/(groebnerMatrix(3,0))-groebnerMatrix(4,97)/(groebnerMatrix(4,0))); groebnerMatrix(33,98) = (groebnerMatrix(3,98)/(groebnerMatrix(3,0))-groebnerMatrix(4,98)/(groebnerMatrix(4,0))); groebnerMatrix(33,99) = (groebnerMatrix(3,99)/(groebnerMatrix(3,0))-groebnerMatrix(4,99)/(groebnerMatrix(4,0))); groebnerMatrix(33,100) = (groebnerMatrix(3,100)/(groebnerMatrix(3,0))-groebnerMatrix(4,100)/(groebnerMatrix(4,0))); groebnerMatrix(33,101) = (groebnerMatrix(3,101)/(groebnerMatrix(3,0))-groebnerMatrix(4,101)/(groebnerMatrix(4,0))); groebnerMatrix(33,103) = (groebnerMatrix(3,103)/(groebnerMatrix(3,0))-groebnerMatrix(4,103)/(groebnerMatrix(4,0))); groebnerMatrix(33,104) = (groebnerMatrix(3,104)/(groebnerMatrix(3,0))-groebnerMatrix(4,104)/(groebnerMatrix(4,0))); groebnerMatrix(33,105) = (groebnerMatrix(3,105)/(groebnerMatrix(3,0))-groebnerMatrix(4,105)/(groebnerMatrix(4,0))); groebnerMatrix(33,106) = (groebnerMatrix(3,106)/(groebnerMatrix(3,0))-groebnerMatrix(4,106)/(groebnerMatrix(4,0))); groebnerMatrix(33,107) = (groebnerMatrix(3,107)/(groebnerMatrix(3,0))-groebnerMatrix(4,107)/(groebnerMatrix(4,0))); groebnerMatrix(33,108) = (groebnerMatrix(3,108)/(groebnerMatrix(3,0))-groebnerMatrix(4,108)/(groebnerMatrix(4,0))); groebnerMatrix(33,109) = (groebnerMatrix(3,109)/(groebnerMatrix(3,0))-groebnerMatrix(4,109)/(groebnerMatrix(4,0))); groebnerMatrix(33,110) = (groebnerMatrix(3,110)/(groebnerMatrix(3,0))-groebnerMatrix(4,110)/(groebnerMatrix(4,0))); groebnerMatrix(33,111) = (groebnerMatrix(3,111)/(groebnerMatrix(3,0))-groebnerMatrix(4,111)/(groebnerMatrix(4,0))); groebnerMatrix(33,112) = (groebnerMatrix(3,112)/(groebnerMatrix(3,0))-groebnerMatrix(4,112)/(groebnerMatrix(4,0))); groebnerMatrix(33,113) = (groebnerMatrix(3,113)/(groebnerMatrix(3,0))-groebnerMatrix(4,113)/(groebnerMatrix(4,0))); groebnerMatrix(33,115) = (groebnerMatrix(3,115)/(groebnerMatrix(3,0))-groebnerMatrix(4,115)/(groebnerMatrix(4,0))); groebnerMatrix(33,116) = (groebnerMatrix(3,116)/(groebnerMatrix(3,0))-groebnerMatrix(4,116)/(groebnerMatrix(4,0))); groebnerMatrix(33,118) = (groebnerMatrix(3,118)/(groebnerMatrix(3,0))-groebnerMatrix(4,118)/(groebnerMatrix(4,0))); groebnerMatrix(33,119) = (groebnerMatrix(3,119)/(groebnerMatrix(3,0))-groebnerMatrix(4,119)/(groebnerMatrix(4,0))); groebnerMatrix(33,120) = (groebnerMatrix(3,120)/(groebnerMatrix(3,0))-groebnerMatrix(4,120)/(groebnerMatrix(4,0))); groebnerMatrix(33,121) = (groebnerMatrix(3,121)/(groebnerMatrix(3,0))-groebnerMatrix(4,121)/(groebnerMatrix(4,0))); groebnerMatrix(33,122) = (groebnerMatrix(3,122)/(groebnerMatrix(3,0))-groebnerMatrix(4,122)/(groebnerMatrix(4,0))); groebnerMatrix(33,123) = (groebnerMatrix(3,123)/(groebnerMatrix(3,0))-groebnerMatrix(4,123)/(groebnerMatrix(4,0))); groebnerMatrix(33,125) = (groebnerMatrix(3,125)/(groebnerMatrix(3,0))-groebnerMatrix(4,125)/(groebnerMatrix(4,0))); groebnerMatrix(33,126) = (groebnerMatrix(3,126)/(groebnerMatrix(3,0))-groebnerMatrix(4,126)/(groebnerMatrix(4,0))); groebnerMatrix(33,127) = (groebnerMatrix(3,127)/(groebnerMatrix(3,0))-groebnerMatrix(4,127)/(groebnerMatrix(4,0))); groebnerMatrix(33,128) = (groebnerMatrix(3,128)/(groebnerMatrix(3,0))-groebnerMatrix(4,128)/(groebnerMatrix(4,0))); groebnerMatrix(33,129) = (groebnerMatrix(3,129)/(groebnerMatrix(3,0))-groebnerMatrix(4,129)/(groebnerMatrix(4,0))); groebnerMatrix(33,130) = (groebnerMatrix(3,130)/(groebnerMatrix(3,0))-groebnerMatrix(4,130)/(groebnerMatrix(4,0))); groebnerMatrix(33,133) = (groebnerMatrix(3,133)/(groebnerMatrix(3,0))-groebnerMatrix(4,133)/(groebnerMatrix(4,0))); groebnerMatrix(33,134) = (groebnerMatrix(3,134)/(groebnerMatrix(3,0))-groebnerMatrix(4,134)/(groebnerMatrix(4,0))); groebnerMatrix(33,136) = (groebnerMatrix(3,136)/(groebnerMatrix(3,0))-groebnerMatrix(4,136)/(groebnerMatrix(4,0))); groebnerMatrix(33,137) = (groebnerMatrix(3,137)/(groebnerMatrix(3,0))-groebnerMatrix(4,137)/(groebnerMatrix(4,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial34( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(34,1) = (groebnerMatrix(4,1)/(groebnerMatrix(4,0))-groebnerMatrix(5,1)/(groebnerMatrix(5,0))); groebnerMatrix(34,2) = (groebnerMatrix(4,2)/(groebnerMatrix(4,0))-groebnerMatrix(5,2)/(groebnerMatrix(5,0))); groebnerMatrix(34,3) = (groebnerMatrix(4,3)/(groebnerMatrix(4,0))-groebnerMatrix(5,3)/(groebnerMatrix(5,0))); groebnerMatrix(34,4) = (groebnerMatrix(4,4)/(groebnerMatrix(4,0))-groebnerMatrix(5,4)/(groebnerMatrix(5,0))); groebnerMatrix(34,5) = (groebnerMatrix(4,5)/(groebnerMatrix(4,0))-groebnerMatrix(5,5)/(groebnerMatrix(5,0))); groebnerMatrix(34,6) = (groebnerMatrix(4,6)/(groebnerMatrix(4,0))-groebnerMatrix(5,6)/(groebnerMatrix(5,0))); groebnerMatrix(34,8) = (groebnerMatrix(4,8)/(groebnerMatrix(4,0))-groebnerMatrix(5,8)/(groebnerMatrix(5,0))); groebnerMatrix(34,10) = (groebnerMatrix(4,10)/(groebnerMatrix(4,0))-groebnerMatrix(5,10)/(groebnerMatrix(5,0))); groebnerMatrix(34,11) = (groebnerMatrix(4,11)/(groebnerMatrix(4,0))-groebnerMatrix(5,11)/(groebnerMatrix(5,0))); groebnerMatrix(34,12) = (groebnerMatrix(4,12)/(groebnerMatrix(4,0))-groebnerMatrix(5,12)/(groebnerMatrix(5,0))); groebnerMatrix(34,13) = (groebnerMatrix(4,13)/(groebnerMatrix(4,0))-groebnerMatrix(5,13)/(groebnerMatrix(5,0))); groebnerMatrix(34,14) = (groebnerMatrix(4,14)/(groebnerMatrix(4,0))-groebnerMatrix(5,14)/(groebnerMatrix(5,0))); groebnerMatrix(34,15) = (groebnerMatrix(4,15)/(groebnerMatrix(4,0))-groebnerMatrix(5,15)/(groebnerMatrix(5,0))); groebnerMatrix(34,16) = (groebnerMatrix(4,16)/(groebnerMatrix(4,0))-groebnerMatrix(5,16)/(groebnerMatrix(5,0))); groebnerMatrix(34,18) = (groebnerMatrix(4,18)/(groebnerMatrix(4,0))-groebnerMatrix(5,18)/(groebnerMatrix(5,0))); groebnerMatrix(34,19) = (groebnerMatrix(4,19)/(groebnerMatrix(4,0))-groebnerMatrix(5,19)/(groebnerMatrix(5,0))); groebnerMatrix(34,20) = (groebnerMatrix(4,20)/(groebnerMatrix(4,0))-groebnerMatrix(5,20)/(groebnerMatrix(5,0))); groebnerMatrix(34,21) = (groebnerMatrix(4,21)/(groebnerMatrix(4,0))-groebnerMatrix(5,21)/(groebnerMatrix(5,0))); groebnerMatrix(34,22) = (groebnerMatrix(4,22)/(groebnerMatrix(4,0))-groebnerMatrix(5,22)/(groebnerMatrix(5,0))); groebnerMatrix(34,23) = (groebnerMatrix(4,23)/(groebnerMatrix(4,0))-groebnerMatrix(5,23)/(groebnerMatrix(5,0))); groebnerMatrix(34,25) = (groebnerMatrix(4,25)/(groebnerMatrix(4,0))-groebnerMatrix(5,25)/(groebnerMatrix(5,0))); groebnerMatrix(34,26) = (groebnerMatrix(4,26)/(groebnerMatrix(4,0))-groebnerMatrix(5,26)/(groebnerMatrix(5,0))); groebnerMatrix(34,27) = (groebnerMatrix(4,27)/(groebnerMatrix(4,0))-groebnerMatrix(5,27)/(groebnerMatrix(5,0))); groebnerMatrix(34,28) = (groebnerMatrix(4,28)/(groebnerMatrix(4,0))-groebnerMatrix(5,28)/(groebnerMatrix(5,0))); groebnerMatrix(34,29) = (groebnerMatrix(4,29)/(groebnerMatrix(4,0))-groebnerMatrix(5,29)/(groebnerMatrix(5,0))); groebnerMatrix(34,30) = (groebnerMatrix(4,30)/(groebnerMatrix(4,0))-groebnerMatrix(5,30)/(groebnerMatrix(5,0))); groebnerMatrix(34,33) = (groebnerMatrix(4,33)/(groebnerMatrix(4,0))-groebnerMatrix(5,33)/(groebnerMatrix(5,0))); groebnerMatrix(34,34) = (groebnerMatrix(4,34)/(groebnerMatrix(4,0))-groebnerMatrix(5,34)/(groebnerMatrix(5,0))); groebnerMatrix(34,39) = (groebnerMatrix(4,39)/(groebnerMatrix(4,0))-groebnerMatrix(5,39)/(groebnerMatrix(5,0))); groebnerMatrix(34,40) = (groebnerMatrix(4,40)/(groebnerMatrix(4,0))-groebnerMatrix(5,40)/(groebnerMatrix(5,0))); groebnerMatrix(34,41) = (groebnerMatrix(4,41)/(groebnerMatrix(4,0))-groebnerMatrix(5,41)/(groebnerMatrix(5,0))); groebnerMatrix(34,42) = (groebnerMatrix(4,42)/(groebnerMatrix(4,0))-groebnerMatrix(5,42)/(groebnerMatrix(5,0))); groebnerMatrix(34,43) = (groebnerMatrix(4,43)/(groebnerMatrix(4,0))-groebnerMatrix(5,43)/(groebnerMatrix(5,0))); groebnerMatrix(34,44) = (groebnerMatrix(4,44)/(groebnerMatrix(4,0))-groebnerMatrix(5,44)/(groebnerMatrix(5,0))); groebnerMatrix(34,45) = (groebnerMatrix(4,45)/(groebnerMatrix(4,0))-groebnerMatrix(5,45)/(groebnerMatrix(5,0))); groebnerMatrix(34,46) = (groebnerMatrix(4,46)/(groebnerMatrix(4,0))-groebnerMatrix(5,46)/(groebnerMatrix(5,0))); groebnerMatrix(34,47) = (groebnerMatrix(4,47)/(groebnerMatrix(4,0))-groebnerMatrix(5,47)/(groebnerMatrix(5,0))); groebnerMatrix(34,48) = (groebnerMatrix(4,48)/(groebnerMatrix(4,0))-groebnerMatrix(5,48)/(groebnerMatrix(5,0))); groebnerMatrix(34,49) = (groebnerMatrix(4,49)/(groebnerMatrix(4,0))-groebnerMatrix(5,49)/(groebnerMatrix(5,0))); groebnerMatrix(34,50) = (groebnerMatrix(4,50)/(groebnerMatrix(4,0))-groebnerMatrix(5,50)/(groebnerMatrix(5,0))); groebnerMatrix(34,51) = (groebnerMatrix(4,51)/(groebnerMatrix(4,0))-groebnerMatrix(5,51)/(groebnerMatrix(5,0))); groebnerMatrix(34,52) = (groebnerMatrix(4,52)/(groebnerMatrix(4,0))-groebnerMatrix(5,52)/(groebnerMatrix(5,0))); groebnerMatrix(34,53) = (groebnerMatrix(4,53)/(groebnerMatrix(4,0))-groebnerMatrix(5,53)/(groebnerMatrix(5,0))); groebnerMatrix(34,54) = (groebnerMatrix(4,54)/(groebnerMatrix(4,0))-groebnerMatrix(5,54)/(groebnerMatrix(5,0))); groebnerMatrix(34,55) = (groebnerMatrix(4,55)/(groebnerMatrix(4,0))-groebnerMatrix(5,55)/(groebnerMatrix(5,0))); groebnerMatrix(34,56) = (groebnerMatrix(4,56)/(groebnerMatrix(4,0))-groebnerMatrix(5,56)/(groebnerMatrix(5,0))); groebnerMatrix(34,57) = (groebnerMatrix(4,57)/(groebnerMatrix(4,0))-groebnerMatrix(5,57)/(groebnerMatrix(5,0))); groebnerMatrix(34,58) = (groebnerMatrix(4,58)/(groebnerMatrix(4,0))-groebnerMatrix(5,58)/(groebnerMatrix(5,0))); groebnerMatrix(34,59) = (groebnerMatrix(4,59)/(groebnerMatrix(4,0))-groebnerMatrix(5,59)/(groebnerMatrix(5,0))); groebnerMatrix(34,60) = (groebnerMatrix(4,60)/(groebnerMatrix(4,0))-groebnerMatrix(5,60)/(groebnerMatrix(5,0))); groebnerMatrix(34,61) = (groebnerMatrix(4,61)/(groebnerMatrix(4,0))-groebnerMatrix(5,61)/(groebnerMatrix(5,0))); groebnerMatrix(34,62) = (groebnerMatrix(4,62)/(groebnerMatrix(4,0))-groebnerMatrix(5,62)/(groebnerMatrix(5,0))); groebnerMatrix(34,64) = (groebnerMatrix(4,64)/(groebnerMatrix(4,0))-groebnerMatrix(5,64)/(groebnerMatrix(5,0))); groebnerMatrix(34,65) = (groebnerMatrix(4,65)/(groebnerMatrix(4,0))-groebnerMatrix(5,65)/(groebnerMatrix(5,0))); groebnerMatrix(34,66) = (groebnerMatrix(4,66)/(groebnerMatrix(4,0))-groebnerMatrix(5,66)/(groebnerMatrix(5,0))); groebnerMatrix(34,67) = (groebnerMatrix(4,67)/(groebnerMatrix(4,0))-groebnerMatrix(5,67)/(groebnerMatrix(5,0))); groebnerMatrix(34,68) = (groebnerMatrix(4,68)/(groebnerMatrix(4,0))-groebnerMatrix(5,68)/(groebnerMatrix(5,0))); groebnerMatrix(34,69) = (groebnerMatrix(4,69)/(groebnerMatrix(4,0))-groebnerMatrix(5,69)/(groebnerMatrix(5,0))); groebnerMatrix(34,70) = (groebnerMatrix(4,70)/(groebnerMatrix(4,0))-groebnerMatrix(5,70)/(groebnerMatrix(5,0))); groebnerMatrix(34,71) = (groebnerMatrix(4,71)/(groebnerMatrix(4,0))-groebnerMatrix(5,71)/(groebnerMatrix(5,0))); groebnerMatrix(34,73) = (groebnerMatrix(4,73)/(groebnerMatrix(4,0))-groebnerMatrix(5,73)/(groebnerMatrix(5,0))); groebnerMatrix(34,74) = (groebnerMatrix(4,74)/(groebnerMatrix(4,0))-groebnerMatrix(5,74)/(groebnerMatrix(5,0))); groebnerMatrix(34,76) = (groebnerMatrix(4,76)/(groebnerMatrix(4,0))-groebnerMatrix(5,76)/(groebnerMatrix(5,0))); groebnerMatrix(34,77) = (groebnerMatrix(4,77)/(groebnerMatrix(4,0))-groebnerMatrix(5,77)/(groebnerMatrix(5,0))); groebnerMatrix(34,78) = (groebnerMatrix(4,78)/(groebnerMatrix(4,0))-groebnerMatrix(5,78)/(groebnerMatrix(5,0))); groebnerMatrix(34,79) = (groebnerMatrix(4,79)/(groebnerMatrix(4,0))-groebnerMatrix(5,79)/(groebnerMatrix(5,0))); groebnerMatrix(34,80) = (groebnerMatrix(4,80)/(groebnerMatrix(4,0))-groebnerMatrix(5,80)/(groebnerMatrix(5,0))); groebnerMatrix(34,81) = (groebnerMatrix(4,81)/(groebnerMatrix(4,0))-groebnerMatrix(5,81)/(groebnerMatrix(5,0))); groebnerMatrix(34,82) = (groebnerMatrix(4,82)/(groebnerMatrix(4,0))-groebnerMatrix(5,82)/(groebnerMatrix(5,0))); groebnerMatrix(34,83) = (groebnerMatrix(4,83)/(groebnerMatrix(4,0))-groebnerMatrix(5,83)/(groebnerMatrix(5,0))); groebnerMatrix(34,84) = (groebnerMatrix(4,84)/(groebnerMatrix(4,0))-groebnerMatrix(5,84)/(groebnerMatrix(5,0))); groebnerMatrix(34,85) = (groebnerMatrix(4,85)/(groebnerMatrix(4,0))-groebnerMatrix(5,85)/(groebnerMatrix(5,0))); groebnerMatrix(34,86) = (groebnerMatrix(4,86)/(groebnerMatrix(4,0))-groebnerMatrix(5,86)/(groebnerMatrix(5,0))); groebnerMatrix(34,87) = (groebnerMatrix(4,87)/(groebnerMatrix(4,0))-groebnerMatrix(5,87)/(groebnerMatrix(5,0))); groebnerMatrix(34,89) = (groebnerMatrix(4,89)/(groebnerMatrix(4,0))-groebnerMatrix(5,89)/(groebnerMatrix(5,0))); groebnerMatrix(34,91) = (groebnerMatrix(4,91)/(groebnerMatrix(4,0))-groebnerMatrix(5,91)/(groebnerMatrix(5,0))); groebnerMatrix(34,92) = (groebnerMatrix(4,92)/(groebnerMatrix(4,0))-groebnerMatrix(5,92)/(groebnerMatrix(5,0))); groebnerMatrix(34,94) = (groebnerMatrix(4,94)/(groebnerMatrix(4,0))-groebnerMatrix(5,94)/(groebnerMatrix(5,0))); groebnerMatrix(34,97) = (groebnerMatrix(4,97)/(groebnerMatrix(4,0))-groebnerMatrix(5,97)/(groebnerMatrix(5,0))); groebnerMatrix(34,98) = (groebnerMatrix(4,98)/(groebnerMatrix(4,0))-groebnerMatrix(5,98)/(groebnerMatrix(5,0))); groebnerMatrix(34,99) = (groebnerMatrix(4,99)/(groebnerMatrix(4,0))-groebnerMatrix(5,99)/(groebnerMatrix(5,0))); groebnerMatrix(34,100) = (groebnerMatrix(4,100)/(groebnerMatrix(4,0))-groebnerMatrix(5,100)/(groebnerMatrix(5,0))); groebnerMatrix(34,101) = (groebnerMatrix(4,101)/(groebnerMatrix(4,0))-groebnerMatrix(5,101)/(groebnerMatrix(5,0))); groebnerMatrix(34,103) = (groebnerMatrix(4,103)/(groebnerMatrix(4,0))-groebnerMatrix(5,103)/(groebnerMatrix(5,0))); groebnerMatrix(34,104) = (groebnerMatrix(4,104)/(groebnerMatrix(4,0))-groebnerMatrix(5,104)/(groebnerMatrix(5,0))); groebnerMatrix(34,105) = (groebnerMatrix(4,105)/(groebnerMatrix(4,0))-groebnerMatrix(5,105)/(groebnerMatrix(5,0))); groebnerMatrix(34,106) = (groebnerMatrix(4,106)/(groebnerMatrix(4,0))-groebnerMatrix(5,106)/(groebnerMatrix(5,0))); groebnerMatrix(34,107) = (groebnerMatrix(4,107)/(groebnerMatrix(4,0))-groebnerMatrix(5,107)/(groebnerMatrix(5,0))); groebnerMatrix(34,108) = (groebnerMatrix(4,108)/(groebnerMatrix(4,0))-groebnerMatrix(5,108)/(groebnerMatrix(5,0))); groebnerMatrix(34,109) = (groebnerMatrix(4,109)/(groebnerMatrix(4,0))-groebnerMatrix(5,109)/(groebnerMatrix(5,0))); groebnerMatrix(34,110) = (groebnerMatrix(4,110)/(groebnerMatrix(4,0))-groebnerMatrix(5,110)/(groebnerMatrix(5,0))); groebnerMatrix(34,111) = (groebnerMatrix(4,111)/(groebnerMatrix(4,0))-groebnerMatrix(5,111)/(groebnerMatrix(5,0))); groebnerMatrix(34,112) = (groebnerMatrix(4,112)/(groebnerMatrix(4,0))-groebnerMatrix(5,112)/(groebnerMatrix(5,0))); groebnerMatrix(34,113) = (groebnerMatrix(4,113)/(groebnerMatrix(4,0))-groebnerMatrix(5,113)/(groebnerMatrix(5,0))); groebnerMatrix(34,115) = (groebnerMatrix(4,115)/(groebnerMatrix(4,0))-groebnerMatrix(5,115)/(groebnerMatrix(5,0))); groebnerMatrix(34,116) = (groebnerMatrix(4,116)/(groebnerMatrix(4,0))-groebnerMatrix(5,116)/(groebnerMatrix(5,0))); groebnerMatrix(34,118) = (groebnerMatrix(4,118)/(groebnerMatrix(4,0))-groebnerMatrix(5,118)/(groebnerMatrix(5,0))); groebnerMatrix(34,119) = (groebnerMatrix(4,119)/(groebnerMatrix(4,0))-groebnerMatrix(5,119)/(groebnerMatrix(5,0))); groebnerMatrix(34,120) = (groebnerMatrix(4,120)/(groebnerMatrix(4,0))-groebnerMatrix(5,120)/(groebnerMatrix(5,0))); groebnerMatrix(34,121) = (groebnerMatrix(4,121)/(groebnerMatrix(4,0))-groebnerMatrix(5,121)/(groebnerMatrix(5,0))); groebnerMatrix(34,122) = (groebnerMatrix(4,122)/(groebnerMatrix(4,0))-groebnerMatrix(5,122)/(groebnerMatrix(5,0))); groebnerMatrix(34,123) = (groebnerMatrix(4,123)/(groebnerMatrix(4,0))-groebnerMatrix(5,123)/(groebnerMatrix(5,0))); groebnerMatrix(34,125) = (groebnerMatrix(4,125)/(groebnerMatrix(4,0))-groebnerMatrix(5,125)/(groebnerMatrix(5,0))); groebnerMatrix(34,126) = (groebnerMatrix(4,126)/(groebnerMatrix(4,0))-groebnerMatrix(5,126)/(groebnerMatrix(5,0))); groebnerMatrix(34,127) = (groebnerMatrix(4,127)/(groebnerMatrix(4,0))-groebnerMatrix(5,127)/(groebnerMatrix(5,0))); groebnerMatrix(34,128) = (groebnerMatrix(4,128)/(groebnerMatrix(4,0))-groebnerMatrix(5,128)/(groebnerMatrix(5,0))); groebnerMatrix(34,129) = (groebnerMatrix(4,129)/(groebnerMatrix(4,0))-groebnerMatrix(5,129)/(groebnerMatrix(5,0))); groebnerMatrix(34,130) = (groebnerMatrix(4,130)/(groebnerMatrix(4,0))-groebnerMatrix(5,130)/(groebnerMatrix(5,0))); groebnerMatrix(34,133) = (groebnerMatrix(4,133)/(groebnerMatrix(4,0))-groebnerMatrix(5,133)/(groebnerMatrix(5,0))); groebnerMatrix(34,134) = (groebnerMatrix(4,134)/(groebnerMatrix(4,0))-groebnerMatrix(5,134)/(groebnerMatrix(5,0))); groebnerMatrix(34,136) = (groebnerMatrix(4,136)/(groebnerMatrix(4,0))-groebnerMatrix(5,136)/(groebnerMatrix(5,0))); groebnerMatrix(34,137) = (groebnerMatrix(4,137)/(groebnerMatrix(4,0))-groebnerMatrix(5,137)/(groebnerMatrix(5,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial35( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(35,1) = (groebnerMatrix(5,1)/(groebnerMatrix(5,0))-groebnerMatrix(6,1)/(groebnerMatrix(6,0))); groebnerMatrix(35,2) = (groebnerMatrix(5,2)/(groebnerMatrix(5,0))-groebnerMatrix(6,2)/(groebnerMatrix(6,0))); groebnerMatrix(35,3) = (groebnerMatrix(5,3)/(groebnerMatrix(5,0))-groebnerMatrix(6,3)/(groebnerMatrix(6,0))); groebnerMatrix(35,4) = (groebnerMatrix(5,4)/(groebnerMatrix(5,0))-groebnerMatrix(6,4)/(groebnerMatrix(6,0))); groebnerMatrix(35,5) = (groebnerMatrix(5,5)/(groebnerMatrix(5,0))-groebnerMatrix(6,5)/(groebnerMatrix(6,0))); groebnerMatrix(35,6) = (groebnerMatrix(5,6)/(groebnerMatrix(5,0))-groebnerMatrix(6,6)/(groebnerMatrix(6,0))); groebnerMatrix(35,8) = (groebnerMatrix(5,8)/(groebnerMatrix(5,0))-groebnerMatrix(6,8)/(groebnerMatrix(6,0))); groebnerMatrix(35,10) = (groebnerMatrix(5,10)/(groebnerMatrix(5,0))-groebnerMatrix(6,10)/(groebnerMatrix(6,0))); groebnerMatrix(35,11) = (groebnerMatrix(5,11)/(groebnerMatrix(5,0))-groebnerMatrix(6,11)/(groebnerMatrix(6,0))); groebnerMatrix(35,12) = (groebnerMatrix(5,12)/(groebnerMatrix(5,0))-groebnerMatrix(6,12)/(groebnerMatrix(6,0))); groebnerMatrix(35,13) = (groebnerMatrix(5,13)/(groebnerMatrix(5,0))-groebnerMatrix(6,13)/(groebnerMatrix(6,0))); groebnerMatrix(35,14) = (groebnerMatrix(5,14)/(groebnerMatrix(5,0))-groebnerMatrix(6,14)/(groebnerMatrix(6,0))); groebnerMatrix(35,15) = (groebnerMatrix(5,15)/(groebnerMatrix(5,0))-groebnerMatrix(6,15)/(groebnerMatrix(6,0))); groebnerMatrix(35,16) = (groebnerMatrix(5,16)/(groebnerMatrix(5,0))-groebnerMatrix(6,16)/(groebnerMatrix(6,0))); groebnerMatrix(35,18) = (groebnerMatrix(5,18)/(groebnerMatrix(5,0))-groebnerMatrix(6,18)/(groebnerMatrix(6,0))); groebnerMatrix(35,19) = (groebnerMatrix(5,19)/(groebnerMatrix(5,0))-groebnerMatrix(6,19)/(groebnerMatrix(6,0))); groebnerMatrix(35,20) = (groebnerMatrix(5,20)/(groebnerMatrix(5,0))-groebnerMatrix(6,20)/(groebnerMatrix(6,0))); groebnerMatrix(35,21) = (groebnerMatrix(5,21)/(groebnerMatrix(5,0))-groebnerMatrix(6,21)/(groebnerMatrix(6,0))); groebnerMatrix(35,22) = (groebnerMatrix(5,22)/(groebnerMatrix(5,0))-groebnerMatrix(6,22)/(groebnerMatrix(6,0))); groebnerMatrix(35,23) = (groebnerMatrix(5,23)/(groebnerMatrix(5,0))-groebnerMatrix(6,23)/(groebnerMatrix(6,0))); groebnerMatrix(35,25) = (groebnerMatrix(5,25)/(groebnerMatrix(5,0))-groebnerMatrix(6,25)/(groebnerMatrix(6,0))); groebnerMatrix(35,26) = (groebnerMatrix(5,26)/(groebnerMatrix(5,0))-groebnerMatrix(6,26)/(groebnerMatrix(6,0))); groebnerMatrix(35,27) = (groebnerMatrix(5,27)/(groebnerMatrix(5,0))-groebnerMatrix(6,27)/(groebnerMatrix(6,0))); groebnerMatrix(35,28) = (groebnerMatrix(5,28)/(groebnerMatrix(5,0))-groebnerMatrix(6,28)/(groebnerMatrix(6,0))); groebnerMatrix(35,29) = (groebnerMatrix(5,29)/(groebnerMatrix(5,0))-groebnerMatrix(6,29)/(groebnerMatrix(6,0))); groebnerMatrix(35,30) = (groebnerMatrix(5,30)/(groebnerMatrix(5,0))-groebnerMatrix(6,30)/(groebnerMatrix(6,0))); groebnerMatrix(35,33) = (groebnerMatrix(5,33)/(groebnerMatrix(5,0))-groebnerMatrix(6,33)/(groebnerMatrix(6,0))); groebnerMatrix(35,34) = (groebnerMatrix(5,34)/(groebnerMatrix(5,0))-groebnerMatrix(6,34)/(groebnerMatrix(6,0))); groebnerMatrix(35,39) = (groebnerMatrix(5,39)/(groebnerMatrix(5,0))-groebnerMatrix(6,39)/(groebnerMatrix(6,0))); groebnerMatrix(35,40) = (groebnerMatrix(5,40)/(groebnerMatrix(5,0))-groebnerMatrix(6,40)/(groebnerMatrix(6,0))); groebnerMatrix(35,41) = (groebnerMatrix(5,41)/(groebnerMatrix(5,0))-groebnerMatrix(6,41)/(groebnerMatrix(6,0))); groebnerMatrix(35,42) = (groebnerMatrix(5,42)/(groebnerMatrix(5,0))-groebnerMatrix(6,42)/(groebnerMatrix(6,0))); groebnerMatrix(35,43) = (groebnerMatrix(5,43)/(groebnerMatrix(5,0))-groebnerMatrix(6,43)/(groebnerMatrix(6,0))); groebnerMatrix(35,44) = (groebnerMatrix(5,44)/(groebnerMatrix(5,0))-groebnerMatrix(6,44)/(groebnerMatrix(6,0))); groebnerMatrix(35,45) = (groebnerMatrix(5,45)/(groebnerMatrix(5,0))-groebnerMatrix(6,45)/(groebnerMatrix(6,0))); groebnerMatrix(35,46) = (groebnerMatrix(5,46)/(groebnerMatrix(5,0))-groebnerMatrix(6,46)/(groebnerMatrix(6,0))); groebnerMatrix(35,47) = (groebnerMatrix(5,47)/(groebnerMatrix(5,0))-groebnerMatrix(6,47)/(groebnerMatrix(6,0))); groebnerMatrix(35,48) = (groebnerMatrix(5,48)/(groebnerMatrix(5,0))-groebnerMatrix(6,48)/(groebnerMatrix(6,0))); groebnerMatrix(35,49) = (groebnerMatrix(5,49)/(groebnerMatrix(5,0))-groebnerMatrix(6,49)/(groebnerMatrix(6,0))); groebnerMatrix(35,50) = (groebnerMatrix(5,50)/(groebnerMatrix(5,0))-groebnerMatrix(6,50)/(groebnerMatrix(6,0))); groebnerMatrix(35,51) = (groebnerMatrix(5,51)/(groebnerMatrix(5,0))-groebnerMatrix(6,51)/(groebnerMatrix(6,0))); groebnerMatrix(35,52) = (groebnerMatrix(5,52)/(groebnerMatrix(5,0))-groebnerMatrix(6,52)/(groebnerMatrix(6,0))); groebnerMatrix(35,53) = (groebnerMatrix(5,53)/(groebnerMatrix(5,0))-groebnerMatrix(6,53)/(groebnerMatrix(6,0))); groebnerMatrix(35,54) = (groebnerMatrix(5,54)/(groebnerMatrix(5,0))-groebnerMatrix(6,54)/(groebnerMatrix(6,0))); groebnerMatrix(35,55) = (groebnerMatrix(5,55)/(groebnerMatrix(5,0))-groebnerMatrix(6,55)/(groebnerMatrix(6,0))); groebnerMatrix(35,56) = (groebnerMatrix(5,56)/(groebnerMatrix(5,0))-groebnerMatrix(6,56)/(groebnerMatrix(6,0))); groebnerMatrix(35,57) = (groebnerMatrix(5,57)/(groebnerMatrix(5,0))-groebnerMatrix(6,57)/(groebnerMatrix(6,0))); groebnerMatrix(35,58) = (groebnerMatrix(5,58)/(groebnerMatrix(5,0))-groebnerMatrix(6,58)/(groebnerMatrix(6,0))); groebnerMatrix(35,59) = (groebnerMatrix(5,59)/(groebnerMatrix(5,0))-groebnerMatrix(6,59)/(groebnerMatrix(6,0))); groebnerMatrix(35,60) = (groebnerMatrix(5,60)/(groebnerMatrix(5,0))-groebnerMatrix(6,60)/(groebnerMatrix(6,0))); groebnerMatrix(35,61) = (groebnerMatrix(5,61)/(groebnerMatrix(5,0))-groebnerMatrix(6,61)/(groebnerMatrix(6,0))); groebnerMatrix(35,62) = (groebnerMatrix(5,62)/(groebnerMatrix(5,0))-groebnerMatrix(6,62)/(groebnerMatrix(6,0))); groebnerMatrix(35,64) = (groebnerMatrix(5,64)/(groebnerMatrix(5,0))-groebnerMatrix(6,64)/(groebnerMatrix(6,0))); groebnerMatrix(35,65) = (groebnerMatrix(5,65)/(groebnerMatrix(5,0))-groebnerMatrix(6,65)/(groebnerMatrix(6,0))); groebnerMatrix(35,66) = (groebnerMatrix(5,66)/(groebnerMatrix(5,0))-groebnerMatrix(6,66)/(groebnerMatrix(6,0))); groebnerMatrix(35,67) = (groebnerMatrix(5,67)/(groebnerMatrix(5,0))-groebnerMatrix(6,67)/(groebnerMatrix(6,0))); groebnerMatrix(35,68) = (groebnerMatrix(5,68)/(groebnerMatrix(5,0))-groebnerMatrix(6,68)/(groebnerMatrix(6,0))); groebnerMatrix(35,69) = (groebnerMatrix(5,69)/(groebnerMatrix(5,0))-groebnerMatrix(6,69)/(groebnerMatrix(6,0))); groebnerMatrix(35,70) = (groebnerMatrix(5,70)/(groebnerMatrix(5,0))-groebnerMatrix(6,70)/(groebnerMatrix(6,0))); groebnerMatrix(35,71) = (groebnerMatrix(5,71)/(groebnerMatrix(5,0))-groebnerMatrix(6,71)/(groebnerMatrix(6,0))); groebnerMatrix(35,73) = (groebnerMatrix(5,73)/(groebnerMatrix(5,0))-groebnerMatrix(6,73)/(groebnerMatrix(6,0))); groebnerMatrix(35,74) = (groebnerMatrix(5,74)/(groebnerMatrix(5,0))-groebnerMatrix(6,74)/(groebnerMatrix(6,0))); groebnerMatrix(35,76) = (groebnerMatrix(5,76)/(groebnerMatrix(5,0))-groebnerMatrix(6,76)/(groebnerMatrix(6,0))); groebnerMatrix(35,77) = (groebnerMatrix(5,77)/(groebnerMatrix(5,0))-groebnerMatrix(6,77)/(groebnerMatrix(6,0))); groebnerMatrix(35,78) = (groebnerMatrix(5,78)/(groebnerMatrix(5,0))-groebnerMatrix(6,78)/(groebnerMatrix(6,0))); groebnerMatrix(35,79) = (groebnerMatrix(5,79)/(groebnerMatrix(5,0))-groebnerMatrix(6,79)/(groebnerMatrix(6,0))); groebnerMatrix(35,80) = (groebnerMatrix(5,80)/(groebnerMatrix(5,0))-groebnerMatrix(6,80)/(groebnerMatrix(6,0))); groebnerMatrix(35,81) = (groebnerMatrix(5,81)/(groebnerMatrix(5,0))-groebnerMatrix(6,81)/(groebnerMatrix(6,0))); groebnerMatrix(35,82) = (groebnerMatrix(5,82)/(groebnerMatrix(5,0))-groebnerMatrix(6,82)/(groebnerMatrix(6,0))); groebnerMatrix(35,83) = (groebnerMatrix(5,83)/(groebnerMatrix(5,0))-groebnerMatrix(6,83)/(groebnerMatrix(6,0))); groebnerMatrix(35,84) = (groebnerMatrix(5,84)/(groebnerMatrix(5,0))-groebnerMatrix(6,84)/(groebnerMatrix(6,0))); groebnerMatrix(35,85) = (groebnerMatrix(5,85)/(groebnerMatrix(5,0))-groebnerMatrix(6,85)/(groebnerMatrix(6,0))); groebnerMatrix(35,86) = (groebnerMatrix(5,86)/(groebnerMatrix(5,0))-groebnerMatrix(6,86)/(groebnerMatrix(6,0))); groebnerMatrix(35,87) = (groebnerMatrix(5,87)/(groebnerMatrix(5,0))-groebnerMatrix(6,87)/(groebnerMatrix(6,0))); groebnerMatrix(35,89) = (groebnerMatrix(5,89)/(groebnerMatrix(5,0))-groebnerMatrix(6,89)/(groebnerMatrix(6,0))); groebnerMatrix(35,91) = (groebnerMatrix(5,91)/(groebnerMatrix(5,0))-groebnerMatrix(6,91)/(groebnerMatrix(6,0))); groebnerMatrix(35,92) = (groebnerMatrix(5,92)/(groebnerMatrix(5,0))-groebnerMatrix(6,92)/(groebnerMatrix(6,0))); groebnerMatrix(35,94) = (groebnerMatrix(5,94)/(groebnerMatrix(5,0))-groebnerMatrix(6,94)/(groebnerMatrix(6,0))); groebnerMatrix(35,97) = (groebnerMatrix(5,97)/(groebnerMatrix(5,0))-groebnerMatrix(6,97)/(groebnerMatrix(6,0))); groebnerMatrix(35,98) = (groebnerMatrix(5,98)/(groebnerMatrix(5,0))-groebnerMatrix(6,98)/(groebnerMatrix(6,0))); groebnerMatrix(35,99) = (groebnerMatrix(5,99)/(groebnerMatrix(5,0))-groebnerMatrix(6,99)/(groebnerMatrix(6,0))); groebnerMatrix(35,100) = (groebnerMatrix(5,100)/(groebnerMatrix(5,0))-groebnerMatrix(6,100)/(groebnerMatrix(6,0))); groebnerMatrix(35,101) = (groebnerMatrix(5,101)/(groebnerMatrix(5,0))-groebnerMatrix(6,101)/(groebnerMatrix(6,0))); groebnerMatrix(35,103) = (groebnerMatrix(5,103)/(groebnerMatrix(5,0))-groebnerMatrix(6,103)/(groebnerMatrix(6,0))); groebnerMatrix(35,104) = (groebnerMatrix(5,104)/(groebnerMatrix(5,0))-groebnerMatrix(6,104)/(groebnerMatrix(6,0))); groebnerMatrix(35,105) = (groebnerMatrix(5,105)/(groebnerMatrix(5,0))-groebnerMatrix(6,105)/(groebnerMatrix(6,0))); groebnerMatrix(35,106) = (groebnerMatrix(5,106)/(groebnerMatrix(5,0))-groebnerMatrix(6,106)/(groebnerMatrix(6,0))); groebnerMatrix(35,107) = (groebnerMatrix(5,107)/(groebnerMatrix(5,0))-groebnerMatrix(6,107)/(groebnerMatrix(6,0))); groebnerMatrix(35,108) = (groebnerMatrix(5,108)/(groebnerMatrix(5,0))-groebnerMatrix(6,108)/(groebnerMatrix(6,0))); groebnerMatrix(35,109) = (groebnerMatrix(5,109)/(groebnerMatrix(5,0))-groebnerMatrix(6,109)/(groebnerMatrix(6,0))); groebnerMatrix(35,110) = (groebnerMatrix(5,110)/(groebnerMatrix(5,0))-groebnerMatrix(6,110)/(groebnerMatrix(6,0))); groebnerMatrix(35,111) = (groebnerMatrix(5,111)/(groebnerMatrix(5,0))-groebnerMatrix(6,111)/(groebnerMatrix(6,0))); groebnerMatrix(35,112) = (groebnerMatrix(5,112)/(groebnerMatrix(5,0))-groebnerMatrix(6,112)/(groebnerMatrix(6,0))); groebnerMatrix(35,113) = (groebnerMatrix(5,113)/(groebnerMatrix(5,0))-groebnerMatrix(6,113)/(groebnerMatrix(6,0))); groebnerMatrix(35,115) = (groebnerMatrix(5,115)/(groebnerMatrix(5,0))-groebnerMatrix(6,115)/(groebnerMatrix(6,0))); groebnerMatrix(35,116) = (groebnerMatrix(5,116)/(groebnerMatrix(5,0))-groebnerMatrix(6,116)/(groebnerMatrix(6,0))); groebnerMatrix(35,118) = (groebnerMatrix(5,118)/(groebnerMatrix(5,0))-groebnerMatrix(6,118)/(groebnerMatrix(6,0))); groebnerMatrix(35,119) = (groebnerMatrix(5,119)/(groebnerMatrix(5,0))-groebnerMatrix(6,119)/(groebnerMatrix(6,0))); groebnerMatrix(35,120) = (groebnerMatrix(5,120)/(groebnerMatrix(5,0))-groebnerMatrix(6,120)/(groebnerMatrix(6,0))); groebnerMatrix(35,121) = (groebnerMatrix(5,121)/(groebnerMatrix(5,0))-groebnerMatrix(6,121)/(groebnerMatrix(6,0))); groebnerMatrix(35,122) = (groebnerMatrix(5,122)/(groebnerMatrix(5,0))-groebnerMatrix(6,122)/(groebnerMatrix(6,0))); groebnerMatrix(35,123) = (groebnerMatrix(5,123)/(groebnerMatrix(5,0))-groebnerMatrix(6,123)/(groebnerMatrix(6,0))); groebnerMatrix(35,125) = (groebnerMatrix(5,125)/(groebnerMatrix(5,0))-groebnerMatrix(6,125)/(groebnerMatrix(6,0))); groebnerMatrix(35,126) = (groebnerMatrix(5,126)/(groebnerMatrix(5,0))-groebnerMatrix(6,126)/(groebnerMatrix(6,0))); groebnerMatrix(35,127) = (groebnerMatrix(5,127)/(groebnerMatrix(5,0))-groebnerMatrix(6,127)/(groebnerMatrix(6,0))); groebnerMatrix(35,128) = (groebnerMatrix(5,128)/(groebnerMatrix(5,0))-groebnerMatrix(6,128)/(groebnerMatrix(6,0))); groebnerMatrix(35,129) = (groebnerMatrix(5,129)/(groebnerMatrix(5,0))-groebnerMatrix(6,129)/(groebnerMatrix(6,0))); groebnerMatrix(35,130) = (groebnerMatrix(5,130)/(groebnerMatrix(5,0))-groebnerMatrix(6,130)/(groebnerMatrix(6,0))); groebnerMatrix(35,133) = (groebnerMatrix(5,133)/(groebnerMatrix(5,0))-groebnerMatrix(6,133)/(groebnerMatrix(6,0))); groebnerMatrix(35,134) = (groebnerMatrix(5,134)/(groebnerMatrix(5,0))-groebnerMatrix(6,134)/(groebnerMatrix(6,0))); groebnerMatrix(35,136) = (groebnerMatrix(5,136)/(groebnerMatrix(5,0))-groebnerMatrix(6,136)/(groebnerMatrix(6,0))); groebnerMatrix(35,137) = (groebnerMatrix(5,137)/(groebnerMatrix(5,0))-groebnerMatrix(6,137)/(groebnerMatrix(6,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial36( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(36,1) = (groebnerMatrix(6,1)/(groebnerMatrix(6,0))-groebnerMatrix(7,1)/(groebnerMatrix(7,0))); groebnerMatrix(36,2) = (groebnerMatrix(6,2)/(groebnerMatrix(6,0))-groebnerMatrix(7,2)/(groebnerMatrix(7,0))); groebnerMatrix(36,3) = (groebnerMatrix(6,3)/(groebnerMatrix(6,0))-groebnerMatrix(7,3)/(groebnerMatrix(7,0))); groebnerMatrix(36,4) = (groebnerMatrix(6,4)/(groebnerMatrix(6,0))-groebnerMatrix(7,4)/(groebnerMatrix(7,0))); groebnerMatrix(36,5) = (groebnerMatrix(6,5)/(groebnerMatrix(6,0))-groebnerMatrix(7,5)/(groebnerMatrix(7,0))); groebnerMatrix(36,6) = (groebnerMatrix(6,6)/(groebnerMatrix(6,0))-groebnerMatrix(7,6)/(groebnerMatrix(7,0))); groebnerMatrix(36,8) = (groebnerMatrix(6,8)/(groebnerMatrix(6,0))-groebnerMatrix(7,8)/(groebnerMatrix(7,0))); groebnerMatrix(36,10) = (groebnerMatrix(6,10)/(groebnerMatrix(6,0))-groebnerMatrix(7,10)/(groebnerMatrix(7,0))); groebnerMatrix(36,11) = (groebnerMatrix(6,11)/(groebnerMatrix(6,0))-groebnerMatrix(7,11)/(groebnerMatrix(7,0))); groebnerMatrix(36,12) = (groebnerMatrix(6,12)/(groebnerMatrix(6,0))-groebnerMatrix(7,12)/(groebnerMatrix(7,0))); groebnerMatrix(36,13) = (groebnerMatrix(6,13)/(groebnerMatrix(6,0))-groebnerMatrix(7,13)/(groebnerMatrix(7,0))); groebnerMatrix(36,14) = (groebnerMatrix(6,14)/(groebnerMatrix(6,0))-groebnerMatrix(7,14)/(groebnerMatrix(7,0))); groebnerMatrix(36,15) = (groebnerMatrix(6,15)/(groebnerMatrix(6,0))-groebnerMatrix(7,15)/(groebnerMatrix(7,0))); groebnerMatrix(36,16) = (groebnerMatrix(6,16)/(groebnerMatrix(6,0))-groebnerMatrix(7,16)/(groebnerMatrix(7,0))); groebnerMatrix(36,18) = (groebnerMatrix(6,18)/(groebnerMatrix(6,0))-groebnerMatrix(7,18)/(groebnerMatrix(7,0))); groebnerMatrix(36,19) = (groebnerMatrix(6,19)/(groebnerMatrix(6,0))-groebnerMatrix(7,19)/(groebnerMatrix(7,0))); groebnerMatrix(36,20) = (groebnerMatrix(6,20)/(groebnerMatrix(6,0))-groebnerMatrix(7,20)/(groebnerMatrix(7,0))); groebnerMatrix(36,21) = (groebnerMatrix(6,21)/(groebnerMatrix(6,0))-groebnerMatrix(7,21)/(groebnerMatrix(7,0))); groebnerMatrix(36,22) = (groebnerMatrix(6,22)/(groebnerMatrix(6,0))-groebnerMatrix(7,22)/(groebnerMatrix(7,0))); groebnerMatrix(36,23) = (groebnerMatrix(6,23)/(groebnerMatrix(6,0))-groebnerMatrix(7,23)/(groebnerMatrix(7,0))); groebnerMatrix(36,25) = (groebnerMatrix(6,25)/(groebnerMatrix(6,0))-groebnerMatrix(7,25)/(groebnerMatrix(7,0))); groebnerMatrix(36,26) = (groebnerMatrix(6,26)/(groebnerMatrix(6,0))-groebnerMatrix(7,26)/(groebnerMatrix(7,0))); groebnerMatrix(36,27) = (groebnerMatrix(6,27)/(groebnerMatrix(6,0))-groebnerMatrix(7,27)/(groebnerMatrix(7,0))); groebnerMatrix(36,28) = (groebnerMatrix(6,28)/(groebnerMatrix(6,0))-groebnerMatrix(7,28)/(groebnerMatrix(7,0))); groebnerMatrix(36,29) = (groebnerMatrix(6,29)/(groebnerMatrix(6,0))-groebnerMatrix(7,29)/(groebnerMatrix(7,0))); groebnerMatrix(36,30) = (groebnerMatrix(6,30)/(groebnerMatrix(6,0))-groebnerMatrix(7,30)/(groebnerMatrix(7,0))); groebnerMatrix(36,33) = (groebnerMatrix(6,33)/(groebnerMatrix(6,0))-groebnerMatrix(7,33)/(groebnerMatrix(7,0))); groebnerMatrix(36,34) = (groebnerMatrix(6,34)/(groebnerMatrix(6,0))-groebnerMatrix(7,34)/(groebnerMatrix(7,0))); groebnerMatrix(36,39) = (groebnerMatrix(6,39)/(groebnerMatrix(6,0))-groebnerMatrix(7,39)/(groebnerMatrix(7,0))); groebnerMatrix(36,40) = (groebnerMatrix(6,40)/(groebnerMatrix(6,0))-groebnerMatrix(7,40)/(groebnerMatrix(7,0))); groebnerMatrix(36,41) = (groebnerMatrix(6,41)/(groebnerMatrix(6,0))-groebnerMatrix(7,41)/(groebnerMatrix(7,0))); groebnerMatrix(36,42) = (groebnerMatrix(6,42)/(groebnerMatrix(6,0))-groebnerMatrix(7,42)/(groebnerMatrix(7,0))); groebnerMatrix(36,43) = (groebnerMatrix(6,43)/(groebnerMatrix(6,0))-groebnerMatrix(7,43)/(groebnerMatrix(7,0))); groebnerMatrix(36,44) = (groebnerMatrix(6,44)/(groebnerMatrix(6,0))-groebnerMatrix(7,44)/(groebnerMatrix(7,0))); groebnerMatrix(36,45) = (groebnerMatrix(6,45)/(groebnerMatrix(6,0))-groebnerMatrix(7,45)/(groebnerMatrix(7,0))); groebnerMatrix(36,46) = (groebnerMatrix(6,46)/(groebnerMatrix(6,0))-groebnerMatrix(7,46)/(groebnerMatrix(7,0))); groebnerMatrix(36,47) = (groebnerMatrix(6,47)/(groebnerMatrix(6,0))-groebnerMatrix(7,47)/(groebnerMatrix(7,0))); groebnerMatrix(36,48) = (groebnerMatrix(6,48)/(groebnerMatrix(6,0))-groebnerMatrix(7,48)/(groebnerMatrix(7,0))); groebnerMatrix(36,49) = (groebnerMatrix(6,49)/(groebnerMatrix(6,0))-groebnerMatrix(7,49)/(groebnerMatrix(7,0))); groebnerMatrix(36,50) = (groebnerMatrix(6,50)/(groebnerMatrix(6,0))-groebnerMatrix(7,50)/(groebnerMatrix(7,0))); groebnerMatrix(36,51) = (groebnerMatrix(6,51)/(groebnerMatrix(6,0))-groebnerMatrix(7,51)/(groebnerMatrix(7,0))); groebnerMatrix(36,52) = (groebnerMatrix(6,52)/(groebnerMatrix(6,0))-groebnerMatrix(7,52)/(groebnerMatrix(7,0))); groebnerMatrix(36,53) = (groebnerMatrix(6,53)/(groebnerMatrix(6,0))-groebnerMatrix(7,53)/(groebnerMatrix(7,0))); groebnerMatrix(36,54) = (groebnerMatrix(6,54)/(groebnerMatrix(6,0))-groebnerMatrix(7,54)/(groebnerMatrix(7,0))); groebnerMatrix(36,55) = (groebnerMatrix(6,55)/(groebnerMatrix(6,0))-groebnerMatrix(7,55)/(groebnerMatrix(7,0))); groebnerMatrix(36,56) = (groebnerMatrix(6,56)/(groebnerMatrix(6,0))-groebnerMatrix(7,56)/(groebnerMatrix(7,0))); groebnerMatrix(36,57) = (groebnerMatrix(6,57)/(groebnerMatrix(6,0))-groebnerMatrix(7,57)/(groebnerMatrix(7,0))); groebnerMatrix(36,58) = (groebnerMatrix(6,58)/(groebnerMatrix(6,0))-groebnerMatrix(7,58)/(groebnerMatrix(7,0))); groebnerMatrix(36,59) = (groebnerMatrix(6,59)/(groebnerMatrix(6,0))-groebnerMatrix(7,59)/(groebnerMatrix(7,0))); groebnerMatrix(36,60) = (groebnerMatrix(6,60)/(groebnerMatrix(6,0))-groebnerMatrix(7,60)/(groebnerMatrix(7,0))); groebnerMatrix(36,61) = (groebnerMatrix(6,61)/(groebnerMatrix(6,0))-groebnerMatrix(7,61)/(groebnerMatrix(7,0))); groebnerMatrix(36,62) = (groebnerMatrix(6,62)/(groebnerMatrix(6,0))-groebnerMatrix(7,62)/(groebnerMatrix(7,0))); groebnerMatrix(36,64) = (groebnerMatrix(6,64)/(groebnerMatrix(6,0))-groebnerMatrix(7,64)/(groebnerMatrix(7,0))); groebnerMatrix(36,65) = (groebnerMatrix(6,65)/(groebnerMatrix(6,0))-groebnerMatrix(7,65)/(groebnerMatrix(7,0))); groebnerMatrix(36,66) = (groebnerMatrix(6,66)/(groebnerMatrix(6,0))-groebnerMatrix(7,66)/(groebnerMatrix(7,0))); groebnerMatrix(36,67) = (groebnerMatrix(6,67)/(groebnerMatrix(6,0))-groebnerMatrix(7,67)/(groebnerMatrix(7,0))); groebnerMatrix(36,68) = (groebnerMatrix(6,68)/(groebnerMatrix(6,0))-groebnerMatrix(7,68)/(groebnerMatrix(7,0))); groebnerMatrix(36,69) = (groebnerMatrix(6,69)/(groebnerMatrix(6,0))-groebnerMatrix(7,69)/(groebnerMatrix(7,0))); groebnerMatrix(36,70) = (groebnerMatrix(6,70)/(groebnerMatrix(6,0))-groebnerMatrix(7,70)/(groebnerMatrix(7,0))); groebnerMatrix(36,71) = (groebnerMatrix(6,71)/(groebnerMatrix(6,0))-groebnerMatrix(7,71)/(groebnerMatrix(7,0))); groebnerMatrix(36,73) = (groebnerMatrix(6,73)/(groebnerMatrix(6,0))-groebnerMatrix(7,73)/(groebnerMatrix(7,0))); groebnerMatrix(36,74) = (groebnerMatrix(6,74)/(groebnerMatrix(6,0))-groebnerMatrix(7,74)/(groebnerMatrix(7,0))); groebnerMatrix(36,76) = (groebnerMatrix(6,76)/(groebnerMatrix(6,0))-groebnerMatrix(7,76)/(groebnerMatrix(7,0))); groebnerMatrix(36,77) = (groebnerMatrix(6,77)/(groebnerMatrix(6,0))-groebnerMatrix(7,77)/(groebnerMatrix(7,0))); groebnerMatrix(36,78) = (groebnerMatrix(6,78)/(groebnerMatrix(6,0))-groebnerMatrix(7,78)/(groebnerMatrix(7,0))); groebnerMatrix(36,79) = (groebnerMatrix(6,79)/(groebnerMatrix(6,0))-groebnerMatrix(7,79)/(groebnerMatrix(7,0))); groebnerMatrix(36,80) = (groebnerMatrix(6,80)/(groebnerMatrix(6,0))-groebnerMatrix(7,80)/(groebnerMatrix(7,0))); groebnerMatrix(36,81) = (groebnerMatrix(6,81)/(groebnerMatrix(6,0))-groebnerMatrix(7,81)/(groebnerMatrix(7,0))); groebnerMatrix(36,82) = (groebnerMatrix(6,82)/(groebnerMatrix(6,0))-groebnerMatrix(7,82)/(groebnerMatrix(7,0))); groebnerMatrix(36,83) = (groebnerMatrix(6,83)/(groebnerMatrix(6,0))-groebnerMatrix(7,83)/(groebnerMatrix(7,0))); groebnerMatrix(36,84) = (groebnerMatrix(6,84)/(groebnerMatrix(6,0))-groebnerMatrix(7,84)/(groebnerMatrix(7,0))); groebnerMatrix(36,85) = (groebnerMatrix(6,85)/(groebnerMatrix(6,0))-groebnerMatrix(7,85)/(groebnerMatrix(7,0))); groebnerMatrix(36,86) = (groebnerMatrix(6,86)/(groebnerMatrix(6,0))-groebnerMatrix(7,86)/(groebnerMatrix(7,0))); groebnerMatrix(36,87) = (groebnerMatrix(6,87)/(groebnerMatrix(6,0))-groebnerMatrix(7,87)/(groebnerMatrix(7,0))); groebnerMatrix(36,89) = (groebnerMatrix(6,89)/(groebnerMatrix(6,0))-groebnerMatrix(7,89)/(groebnerMatrix(7,0))); groebnerMatrix(36,91) = (groebnerMatrix(6,91)/(groebnerMatrix(6,0))-groebnerMatrix(7,91)/(groebnerMatrix(7,0))); groebnerMatrix(36,92) = (groebnerMatrix(6,92)/(groebnerMatrix(6,0))-groebnerMatrix(7,92)/(groebnerMatrix(7,0))); groebnerMatrix(36,94) = (groebnerMatrix(6,94)/(groebnerMatrix(6,0))-groebnerMatrix(7,94)/(groebnerMatrix(7,0))); groebnerMatrix(36,97) = (groebnerMatrix(6,97)/(groebnerMatrix(6,0))-groebnerMatrix(7,97)/(groebnerMatrix(7,0))); groebnerMatrix(36,98) = (groebnerMatrix(6,98)/(groebnerMatrix(6,0))-groebnerMatrix(7,98)/(groebnerMatrix(7,0))); groebnerMatrix(36,99) = (groebnerMatrix(6,99)/(groebnerMatrix(6,0))-groebnerMatrix(7,99)/(groebnerMatrix(7,0))); groebnerMatrix(36,100) = (groebnerMatrix(6,100)/(groebnerMatrix(6,0))-groebnerMatrix(7,100)/(groebnerMatrix(7,0))); groebnerMatrix(36,101) = (groebnerMatrix(6,101)/(groebnerMatrix(6,0))-groebnerMatrix(7,101)/(groebnerMatrix(7,0))); groebnerMatrix(36,103) = (groebnerMatrix(6,103)/(groebnerMatrix(6,0))-groebnerMatrix(7,103)/(groebnerMatrix(7,0))); groebnerMatrix(36,104) = (groebnerMatrix(6,104)/(groebnerMatrix(6,0))-groebnerMatrix(7,104)/(groebnerMatrix(7,0))); groebnerMatrix(36,105) = (groebnerMatrix(6,105)/(groebnerMatrix(6,0))-groebnerMatrix(7,105)/(groebnerMatrix(7,0))); groebnerMatrix(36,106) = (groebnerMatrix(6,106)/(groebnerMatrix(6,0))-groebnerMatrix(7,106)/(groebnerMatrix(7,0))); groebnerMatrix(36,107) = (groebnerMatrix(6,107)/(groebnerMatrix(6,0))-groebnerMatrix(7,107)/(groebnerMatrix(7,0))); groebnerMatrix(36,108) = (groebnerMatrix(6,108)/(groebnerMatrix(6,0))-groebnerMatrix(7,108)/(groebnerMatrix(7,0))); groebnerMatrix(36,109) = (groebnerMatrix(6,109)/(groebnerMatrix(6,0))-groebnerMatrix(7,109)/(groebnerMatrix(7,0))); groebnerMatrix(36,110) = (groebnerMatrix(6,110)/(groebnerMatrix(6,0))-groebnerMatrix(7,110)/(groebnerMatrix(7,0))); groebnerMatrix(36,111) = (groebnerMatrix(6,111)/(groebnerMatrix(6,0))-groebnerMatrix(7,111)/(groebnerMatrix(7,0))); groebnerMatrix(36,112) = (groebnerMatrix(6,112)/(groebnerMatrix(6,0))-groebnerMatrix(7,112)/(groebnerMatrix(7,0))); groebnerMatrix(36,113) = (groebnerMatrix(6,113)/(groebnerMatrix(6,0))-groebnerMatrix(7,113)/(groebnerMatrix(7,0))); groebnerMatrix(36,115) = (groebnerMatrix(6,115)/(groebnerMatrix(6,0))-groebnerMatrix(7,115)/(groebnerMatrix(7,0))); groebnerMatrix(36,116) = (groebnerMatrix(6,116)/(groebnerMatrix(6,0))-groebnerMatrix(7,116)/(groebnerMatrix(7,0))); groebnerMatrix(36,118) = (groebnerMatrix(6,118)/(groebnerMatrix(6,0))-groebnerMatrix(7,118)/(groebnerMatrix(7,0))); groebnerMatrix(36,119) = (groebnerMatrix(6,119)/(groebnerMatrix(6,0))-groebnerMatrix(7,119)/(groebnerMatrix(7,0))); groebnerMatrix(36,120) = (groebnerMatrix(6,120)/(groebnerMatrix(6,0))-groebnerMatrix(7,120)/(groebnerMatrix(7,0))); groebnerMatrix(36,121) = (groebnerMatrix(6,121)/(groebnerMatrix(6,0))-groebnerMatrix(7,121)/(groebnerMatrix(7,0))); groebnerMatrix(36,122) = (groebnerMatrix(6,122)/(groebnerMatrix(6,0))-groebnerMatrix(7,122)/(groebnerMatrix(7,0))); groebnerMatrix(36,123) = (groebnerMatrix(6,123)/(groebnerMatrix(6,0))-groebnerMatrix(7,123)/(groebnerMatrix(7,0))); groebnerMatrix(36,125) = (groebnerMatrix(6,125)/(groebnerMatrix(6,0))-groebnerMatrix(7,125)/(groebnerMatrix(7,0))); groebnerMatrix(36,126) = (groebnerMatrix(6,126)/(groebnerMatrix(6,0))-groebnerMatrix(7,126)/(groebnerMatrix(7,0))); groebnerMatrix(36,127) = (groebnerMatrix(6,127)/(groebnerMatrix(6,0))-groebnerMatrix(7,127)/(groebnerMatrix(7,0))); groebnerMatrix(36,128) = (groebnerMatrix(6,128)/(groebnerMatrix(6,0))-groebnerMatrix(7,128)/(groebnerMatrix(7,0))); groebnerMatrix(36,129) = (groebnerMatrix(6,129)/(groebnerMatrix(6,0))-groebnerMatrix(7,129)/(groebnerMatrix(7,0))); groebnerMatrix(36,130) = (groebnerMatrix(6,130)/(groebnerMatrix(6,0))-groebnerMatrix(7,130)/(groebnerMatrix(7,0))); groebnerMatrix(36,133) = (groebnerMatrix(6,133)/(groebnerMatrix(6,0))-groebnerMatrix(7,133)/(groebnerMatrix(7,0))); groebnerMatrix(36,134) = (groebnerMatrix(6,134)/(groebnerMatrix(6,0))-groebnerMatrix(7,134)/(groebnerMatrix(7,0))); groebnerMatrix(36,136) = (groebnerMatrix(6,136)/(groebnerMatrix(6,0))-groebnerMatrix(7,136)/(groebnerMatrix(7,0))); groebnerMatrix(36,137) = (groebnerMatrix(6,137)/(groebnerMatrix(6,0))-groebnerMatrix(7,137)/(groebnerMatrix(7,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial37( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(37,1) = (groebnerMatrix(7,1)/(groebnerMatrix(7,0))-groebnerMatrix(8,1)/(groebnerMatrix(8,0))); groebnerMatrix(37,2) = (groebnerMatrix(7,2)/(groebnerMatrix(7,0))-groebnerMatrix(8,2)/(groebnerMatrix(8,0))); groebnerMatrix(37,3) = (groebnerMatrix(7,3)/(groebnerMatrix(7,0))-groebnerMatrix(8,3)/(groebnerMatrix(8,0))); groebnerMatrix(37,4) = (groebnerMatrix(7,4)/(groebnerMatrix(7,0))-groebnerMatrix(8,4)/(groebnerMatrix(8,0))); groebnerMatrix(37,5) = (groebnerMatrix(7,5)/(groebnerMatrix(7,0))-groebnerMatrix(8,5)/(groebnerMatrix(8,0))); groebnerMatrix(37,6) = (groebnerMatrix(7,6)/(groebnerMatrix(7,0))-groebnerMatrix(8,6)/(groebnerMatrix(8,0))); groebnerMatrix(37,8) = (groebnerMatrix(7,8)/(groebnerMatrix(7,0))-groebnerMatrix(8,8)/(groebnerMatrix(8,0))); groebnerMatrix(37,10) = (groebnerMatrix(7,10)/(groebnerMatrix(7,0))-groebnerMatrix(8,10)/(groebnerMatrix(8,0))); groebnerMatrix(37,11) = (groebnerMatrix(7,11)/(groebnerMatrix(7,0))-groebnerMatrix(8,11)/(groebnerMatrix(8,0))); groebnerMatrix(37,12) = (groebnerMatrix(7,12)/(groebnerMatrix(7,0))-groebnerMatrix(8,12)/(groebnerMatrix(8,0))); groebnerMatrix(37,13) = (groebnerMatrix(7,13)/(groebnerMatrix(7,0))-groebnerMatrix(8,13)/(groebnerMatrix(8,0))); groebnerMatrix(37,14) = (groebnerMatrix(7,14)/(groebnerMatrix(7,0))-groebnerMatrix(8,14)/(groebnerMatrix(8,0))); groebnerMatrix(37,15) = (groebnerMatrix(7,15)/(groebnerMatrix(7,0))-groebnerMatrix(8,15)/(groebnerMatrix(8,0))); groebnerMatrix(37,16) = (groebnerMatrix(7,16)/(groebnerMatrix(7,0))-groebnerMatrix(8,16)/(groebnerMatrix(8,0))); groebnerMatrix(37,18) = (groebnerMatrix(7,18)/(groebnerMatrix(7,0))-groebnerMatrix(8,18)/(groebnerMatrix(8,0))); groebnerMatrix(37,19) = (groebnerMatrix(7,19)/(groebnerMatrix(7,0))-groebnerMatrix(8,19)/(groebnerMatrix(8,0))); groebnerMatrix(37,20) = (groebnerMatrix(7,20)/(groebnerMatrix(7,0))-groebnerMatrix(8,20)/(groebnerMatrix(8,0))); groebnerMatrix(37,21) = (groebnerMatrix(7,21)/(groebnerMatrix(7,0))-groebnerMatrix(8,21)/(groebnerMatrix(8,0))); groebnerMatrix(37,22) = (groebnerMatrix(7,22)/(groebnerMatrix(7,0))-groebnerMatrix(8,22)/(groebnerMatrix(8,0))); groebnerMatrix(37,23) = (groebnerMatrix(7,23)/(groebnerMatrix(7,0))-groebnerMatrix(8,23)/(groebnerMatrix(8,0))); groebnerMatrix(37,25) = (groebnerMatrix(7,25)/(groebnerMatrix(7,0))-groebnerMatrix(8,25)/(groebnerMatrix(8,0))); groebnerMatrix(37,26) = (groebnerMatrix(7,26)/(groebnerMatrix(7,0))-groebnerMatrix(8,26)/(groebnerMatrix(8,0))); groebnerMatrix(37,27) = (groebnerMatrix(7,27)/(groebnerMatrix(7,0))-groebnerMatrix(8,27)/(groebnerMatrix(8,0))); groebnerMatrix(37,28) = (groebnerMatrix(7,28)/(groebnerMatrix(7,0))-groebnerMatrix(8,28)/(groebnerMatrix(8,0))); groebnerMatrix(37,29) = (groebnerMatrix(7,29)/(groebnerMatrix(7,0))-groebnerMatrix(8,29)/(groebnerMatrix(8,0))); groebnerMatrix(37,30) = (groebnerMatrix(7,30)/(groebnerMatrix(7,0))-groebnerMatrix(8,30)/(groebnerMatrix(8,0))); groebnerMatrix(37,33) = (groebnerMatrix(7,33)/(groebnerMatrix(7,0))-groebnerMatrix(8,33)/(groebnerMatrix(8,0))); groebnerMatrix(37,34) = (groebnerMatrix(7,34)/(groebnerMatrix(7,0))-groebnerMatrix(8,34)/(groebnerMatrix(8,0))); groebnerMatrix(37,39) = (groebnerMatrix(7,39)/(groebnerMatrix(7,0))-groebnerMatrix(8,39)/(groebnerMatrix(8,0))); groebnerMatrix(37,40) = (groebnerMatrix(7,40)/(groebnerMatrix(7,0))-groebnerMatrix(8,40)/(groebnerMatrix(8,0))); groebnerMatrix(37,41) = (groebnerMatrix(7,41)/(groebnerMatrix(7,0))-groebnerMatrix(8,41)/(groebnerMatrix(8,0))); groebnerMatrix(37,42) = (groebnerMatrix(7,42)/(groebnerMatrix(7,0))-groebnerMatrix(8,42)/(groebnerMatrix(8,0))); groebnerMatrix(37,43) = (groebnerMatrix(7,43)/(groebnerMatrix(7,0))-groebnerMatrix(8,43)/(groebnerMatrix(8,0))); groebnerMatrix(37,44) = (groebnerMatrix(7,44)/(groebnerMatrix(7,0))-groebnerMatrix(8,44)/(groebnerMatrix(8,0))); groebnerMatrix(37,45) = (groebnerMatrix(7,45)/(groebnerMatrix(7,0))-groebnerMatrix(8,45)/(groebnerMatrix(8,0))); groebnerMatrix(37,46) = (groebnerMatrix(7,46)/(groebnerMatrix(7,0))-groebnerMatrix(8,46)/(groebnerMatrix(8,0))); groebnerMatrix(37,47) = (groebnerMatrix(7,47)/(groebnerMatrix(7,0))-groebnerMatrix(8,47)/(groebnerMatrix(8,0))); groebnerMatrix(37,48) = (groebnerMatrix(7,48)/(groebnerMatrix(7,0))-groebnerMatrix(8,48)/(groebnerMatrix(8,0))); groebnerMatrix(37,49) = (groebnerMatrix(7,49)/(groebnerMatrix(7,0))-groebnerMatrix(8,49)/(groebnerMatrix(8,0))); groebnerMatrix(37,50) = (groebnerMatrix(7,50)/(groebnerMatrix(7,0))-groebnerMatrix(8,50)/(groebnerMatrix(8,0))); groebnerMatrix(37,51) = (groebnerMatrix(7,51)/(groebnerMatrix(7,0))-groebnerMatrix(8,51)/(groebnerMatrix(8,0))); groebnerMatrix(37,52) = (groebnerMatrix(7,52)/(groebnerMatrix(7,0))-groebnerMatrix(8,52)/(groebnerMatrix(8,0))); groebnerMatrix(37,53) = (groebnerMatrix(7,53)/(groebnerMatrix(7,0))-groebnerMatrix(8,53)/(groebnerMatrix(8,0))); groebnerMatrix(37,54) = (groebnerMatrix(7,54)/(groebnerMatrix(7,0))-groebnerMatrix(8,54)/(groebnerMatrix(8,0))); groebnerMatrix(37,55) = (groebnerMatrix(7,55)/(groebnerMatrix(7,0))-groebnerMatrix(8,55)/(groebnerMatrix(8,0))); groebnerMatrix(37,56) = (groebnerMatrix(7,56)/(groebnerMatrix(7,0))-groebnerMatrix(8,56)/(groebnerMatrix(8,0))); groebnerMatrix(37,57) = (groebnerMatrix(7,57)/(groebnerMatrix(7,0))-groebnerMatrix(8,57)/(groebnerMatrix(8,0))); groebnerMatrix(37,58) = (groebnerMatrix(7,58)/(groebnerMatrix(7,0))-groebnerMatrix(8,58)/(groebnerMatrix(8,0))); groebnerMatrix(37,59) = (groebnerMatrix(7,59)/(groebnerMatrix(7,0))-groebnerMatrix(8,59)/(groebnerMatrix(8,0))); groebnerMatrix(37,60) = (groebnerMatrix(7,60)/(groebnerMatrix(7,0))-groebnerMatrix(8,60)/(groebnerMatrix(8,0))); groebnerMatrix(37,61) = (groebnerMatrix(7,61)/(groebnerMatrix(7,0))-groebnerMatrix(8,61)/(groebnerMatrix(8,0))); groebnerMatrix(37,62) = (groebnerMatrix(7,62)/(groebnerMatrix(7,0))-groebnerMatrix(8,62)/(groebnerMatrix(8,0))); groebnerMatrix(37,64) = (groebnerMatrix(7,64)/(groebnerMatrix(7,0))-groebnerMatrix(8,64)/(groebnerMatrix(8,0))); groebnerMatrix(37,65) = (groebnerMatrix(7,65)/(groebnerMatrix(7,0))-groebnerMatrix(8,65)/(groebnerMatrix(8,0))); groebnerMatrix(37,66) = (groebnerMatrix(7,66)/(groebnerMatrix(7,0))-groebnerMatrix(8,66)/(groebnerMatrix(8,0))); groebnerMatrix(37,67) = (groebnerMatrix(7,67)/(groebnerMatrix(7,0))-groebnerMatrix(8,67)/(groebnerMatrix(8,0))); groebnerMatrix(37,68) = (groebnerMatrix(7,68)/(groebnerMatrix(7,0))-groebnerMatrix(8,68)/(groebnerMatrix(8,0))); groebnerMatrix(37,69) = (groebnerMatrix(7,69)/(groebnerMatrix(7,0))-groebnerMatrix(8,69)/(groebnerMatrix(8,0))); groebnerMatrix(37,70) = (groebnerMatrix(7,70)/(groebnerMatrix(7,0))-groebnerMatrix(8,70)/(groebnerMatrix(8,0))); groebnerMatrix(37,71) = (groebnerMatrix(7,71)/(groebnerMatrix(7,0))-groebnerMatrix(8,71)/(groebnerMatrix(8,0))); groebnerMatrix(37,73) = (groebnerMatrix(7,73)/(groebnerMatrix(7,0))-groebnerMatrix(8,73)/(groebnerMatrix(8,0))); groebnerMatrix(37,74) = (groebnerMatrix(7,74)/(groebnerMatrix(7,0))-groebnerMatrix(8,74)/(groebnerMatrix(8,0))); groebnerMatrix(37,76) = (groebnerMatrix(7,76)/(groebnerMatrix(7,0))-groebnerMatrix(8,76)/(groebnerMatrix(8,0))); groebnerMatrix(37,77) = (groebnerMatrix(7,77)/(groebnerMatrix(7,0))-groebnerMatrix(8,77)/(groebnerMatrix(8,0))); groebnerMatrix(37,78) = (groebnerMatrix(7,78)/(groebnerMatrix(7,0))-groebnerMatrix(8,78)/(groebnerMatrix(8,0))); groebnerMatrix(37,79) = (groebnerMatrix(7,79)/(groebnerMatrix(7,0))-groebnerMatrix(8,79)/(groebnerMatrix(8,0))); groebnerMatrix(37,80) = (groebnerMatrix(7,80)/(groebnerMatrix(7,0))-groebnerMatrix(8,80)/(groebnerMatrix(8,0))); groebnerMatrix(37,81) = (groebnerMatrix(7,81)/(groebnerMatrix(7,0))-groebnerMatrix(8,81)/(groebnerMatrix(8,0))); groebnerMatrix(37,82) = (groebnerMatrix(7,82)/(groebnerMatrix(7,0))-groebnerMatrix(8,82)/(groebnerMatrix(8,0))); groebnerMatrix(37,83) = (groebnerMatrix(7,83)/(groebnerMatrix(7,0))-groebnerMatrix(8,83)/(groebnerMatrix(8,0))); groebnerMatrix(37,84) = (groebnerMatrix(7,84)/(groebnerMatrix(7,0))-groebnerMatrix(8,84)/(groebnerMatrix(8,0))); groebnerMatrix(37,85) = (groebnerMatrix(7,85)/(groebnerMatrix(7,0))-groebnerMatrix(8,85)/(groebnerMatrix(8,0))); groebnerMatrix(37,86) = (groebnerMatrix(7,86)/(groebnerMatrix(7,0))-groebnerMatrix(8,86)/(groebnerMatrix(8,0))); groebnerMatrix(37,87) = (groebnerMatrix(7,87)/(groebnerMatrix(7,0))-groebnerMatrix(8,87)/(groebnerMatrix(8,0))); groebnerMatrix(37,89) = (groebnerMatrix(7,89)/(groebnerMatrix(7,0))-groebnerMatrix(8,89)/(groebnerMatrix(8,0))); groebnerMatrix(37,91) = (groebnerMatrix(7,91)/(groebnerMatrix(7,0))-groebnerMatrix(8,91)/(groebnerMatrix(8,0))); groebnerMatrix(37,92) = (groebnerMatrix(7,92)/(groebnerMatrix(7,0))-groebnerMatrix(8,92)/(groebnerMatrix(8,0))); groebnerMatrix(37,94) = (groebnerMatrix(7,94)/(groebnerMatrix(7,0))-groebnerMatrix(8,94)/(groebnerMatrix(8,0))); groebnerMatrix(37,97) = (groebnerMatrix(7,97)/(groebnerMatrix(7,0))-groebnerMatrix(8,97)/(groebnerMatrix(8,0))); groebnerMatrix(37,98) = (groebnerMatrix(7,98)/(groebnerMatrix(7,0))-groebnerMatrix(8,98)/(groebnerMatrix(8,0))); groebnerMatrix(37,99) = (groebnerMatrix(7,99)/(groebnerMatrix(7,0))-groebnerMatrix(8,99)/(groebnerMatrix(8,0))); groebnerMatrix(37,100) = (groebnerMatrix(7,100)/(groebnerMatrix(7,0))-groebnerMatrix(8,100)/(groebnerMatrix(8,0))); groebnerMatrix(37,101) = (groebnerMatrix(7,101)/(groebnerMatrix(7,0))-groebnerMatrix(8,101)/(groebnerMatrix(8,0))); groebnerMatrix(37,103) = (groebnerMatrix(7,103)/(groebnerMatrix(7,0))-groebnerMatrix(8,103)/(groebnerMatrix(8,0))); groebnerMatrix(37,104) = (groebnerMatrix(7,104)/(groebnerMatrix(7,0))-groebnerMatrix(8,104)/(groebnerMatrix(8,0))); groebnerMatrix(37,105) = (groebnerMatrix(7,105)/(groebnerMatrix(7,0))-groebnerMatrix(8,105)/(groebnerMatrix(8,0))); groebnerMatrix(37,106) = (groebnerMatrix(7,106)/(groebnerMatrix(7,0))-groebnerMatrix(8,106)/(groebnerMatrix(8,0))); groebnerMatrix(37,107) = (groebnerMatrix(7,107)/(groebnerMatrix(7,0))-groebnerMatrix(8,107)/(groebnerMatrix(8,0))); groebnerMatrix(37,108) = (groebnerMatrix(7,108)/(groebnerMatrix(7,0))-groebnerMatrix(8,108)/(groebnerMatrix(8,0))); groebnerMatrix(37,109) = (groebnerMatrix(7,109)/(groebnerMatrix(7,0))-groebnerMatrix(8,109)/(groebnerMatrix(8,0))); groebnerMatrix(37,110) = (groebnerMatrix(7,110)/(groebnerMatrix(7,0))-groebnerMatrix(8,110)/(groebnerMatrix(8,0))); groebnerMatrix(37,111) = (groebnerMatrix(7,111)/(groebnerMatrix(7,0))-groebnerMatrix(8,111)/(groebnerMatrix(8,0))); groebnerMatrix(37,112) = (groebnerMatrix(7,112)/(groebnerMatrix(7,0))-groebnerMatrix(8,112)/(groebnerMatrix(8,0))); groebnerMatrix(37,113) = (groebnerMatrix(7,113)/(groebnerMatrix(7,0))-groebnerMatrix(8,113)/(groebnerMatrix(8,0))); groebnerMatrix(37,115) = (groebnerMatrix(7,115)/(groebnerMatrix(7,0))-groebnerMatrix(8,115)/(groebnerMatrix(8,0))); groebnerMatrix(37,116) = (groebnerMatrix(7,116)/(groebnerMatrix(7,0))-groebnerMatrix(8,116)/(groebnerMatrix(8,0))); groebnerMatrix(37,118) = (groebnerMatrix(7,118)/(groebnerMatrix(7,0))-groebnerMatrix(8,118)/(groebnerMatrix(8,0))); groebnerMatrix(37,119) = (groebnerMatrix(7,119)/(groebnerMatrix(7,0))-groebnerMatrix(8,119)/(groebnerMatrix(8,0))); groebnerMatrix(37,120) = (groebnerMatrix(7,120)/(groebnerMatrix(7,0))-groebnerMatrix(8,120)/(groebnerMatrix(8,0))); groebnerMatrix(37,121) = (groebnerMatrix(7,121)/(groebnerMatrix(7,0))-groebnerMatrix(8,121)/(groebnerMatrix(8,0))); groebnerMatrix(37,122) = (groebnerMatrix(7,122)/(groebnerMatrix(7,0))-groebnerMatrix(8,122)/(groebnerMatrix(8,0))); groebnerMatrix(37,123) = (groebnerMatrix(7,123)/(groebnerMatrix(7,0))-groebnerMatrix(8,123)/(groebnerMatrix(8,0))); groebnerMatrix(37,125) = (groebnerMatrix(7,125)/(groebnerMatrix(7,0))-groebnerMatrix(8,125)/(groebnerMatrix(8,0))); groebnerMatrix(37,126) = (groebnerMatrix(7,126)/(groebnerMatrix(7,0))-groebnerMatrix(8,126)/(groebnerMatrix(8,0))); groebnerMatrix(37,127) = (groebnerMatrix(7,127)/(groebnerMatrix(7,0))-groebnerMatrix(8,127)/(groebnerMatrix(8,0))); groebnerMatrix(37,128) = (groebnerMatrix(7,128)/(groebnerMatrix(7,0))-groebnerMatrix(8,128)/(groebnerMatrix(8,0))); groebnerMatrix(37,129) = (groebnerMatrix(7,129)/(groebnerMatrix(7,0))-groebnerMatrix(8,129)/(groebnerMatrix(8,0))); groebnerMatrix(37,130) = (groebnerMatrix(7,130)/(groebnerMatrix(7,0))-groebnerMatrix(8,130)/(groebnerMatrix(8,0))); groebnerMatrix(37,133) = (groebnerMatrix(7,133)/(groebnerMatrix(7,0))-groebnerMatrix(8,133)/(groebnerMatrix(8,0))); groebnerMatrix(37,134) = (groebnerMatrix(7,134)/(groebnerMatrix(7,0))-groebnerMatrix(8,134)/(groebnerMatrix(8,0))); groebnerMatrix(37,136) = (groebnerMatrix(7,136)/(groebnerMatrix(7,0))-groebnerMatrix(8,136)/(groebnerMatrix(8,0))); groebnerMatrix(37,137) = (groebnerMatrix(7,137)/(groebnerMatrix(7,0))-groebnerMatrix(8,137)/(groebnerMatrix(8,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial38( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(38,1) = (groebnerMatrix(8,1)/(groebnerMatrix(8,0))-groebnerMatrix(9,1)/(groebnerMatrix(9,0))); groebnerMatrix(38,2) = (groebnerMatrix(8,2)/(groebnerMatrix(8,0))-groebnerMatrix(9,2)/(groebnerMatrix(9,0))); groebnerMatrix(38,3) = (groebnerMatrix(8,3)/(groebnerMatrix(8,0))-groebnerMatrix(9,3)/(groebnerMatrix(9,0))); groebnerMatrix(38,4) = (groebnerMatrix(8,4)/(groebnerMatrix(8,0))-groebnerMatrix(9,4)/(groebnerMatrix(9,0))); groebnerMatrix(38,5) = (groebnerMatrix(8,5)/(groebnerMatrix(8,0))-groebnerMatrix(9,5)/(groebnerMatrix(9,0))); groebnerMatrix(38,6) = (groebnerMatrix(8,6)/(groebnerMatrix(8,0))-groebnerMatrix(9,6)/(groebnerMatrix(9,0))); groebnerMatrix(38,8) = (groebnerMatrix(8,8)/(groebnerMatrix(8,0))-groebnerMatrix(9,8)/(groebnerMatrix(9,0))); groebnerMatrix(38,10) = (groebnerMatrix(8,10)/(groebnerMatrix(8,0))-groebnerMatrix(9,10)/(groebnerMatrix(9,0))); groebnerMatrix(38,11) = (groebnerMatrix(8,11)/(groebnerMatrix(8,0))-groebnerMatrix(9,11)/(groebnerMatrix(9,0))); groebnerMatrix(38,12) = (groebnerMatrix(8,12)/(groebnerMatrix(8,0))-groebnerMatrix(9,12)/(groebnerMatrix(9,0))); groebnerMatrix(38,13) = (groebnerMatrix(8,13)/(groebnerMatrix(8,0))-groebnerMatrix(9,13)/(groebnerMatrix(9,0))); groebnerMatrix(38,14) = (groebnerMatrix(8,14)/(groebnerMatrix(8,0))-groebnerMatrix(9,14)/(groebnerMatrix(9,0))); groebnerMatrix(38,15) = (groebnerMatrix(8,15)/(groebnerMatrix(8,0))-groebnerMatrix(9,15)/(groebnerMatrix(9,0))); groebnerMatrix(38,16) = (groebnerMatrix(8,16)/(groebnerMatrix(8,0))-groebnerMatrix(9,16)/(groebnerMatrix(9,0))); groebnerMatrix(38,18) = (groebnerMatrix(8,18)/(groebnerMatrix(8,0))-groebnerMatrix(9,18)/(groebnerMatrix(9,0))); groebnerMatrix(38,19) = (groebnerMatrix(8,19)/(groebnerMatrix(8,0))-groebnerMatrix(9,19)/(groebnerMatrix(9,0))); groebnerMatrix(38,20) = (groebnerMatrix(8,20)/(groebnerMatrix(8,0))-groebnerMatrix(9,20)/(groebnerMatrix(9,0))); groebnerMatrix(38,21) = (groebnerMatrix(8,21)/(groebnerMatrix(8,0))-groebnerMatrix(9,21)/(groebnerMatrix(9,0))); groebnerMatrix(38,22) = (groebnerMatrix(8,22)/(groebnerMatrix(8,0))-groebnerMatrix(9,22)/(groebnerMatrix(9,0))); groebnerMatrix(38,23) = (groebnerMatrix(8,23)/(groebnerMatrix(8,0))-groebnerMatrix(9,23)/(groebnerMatrix(9,0))); groebnerMatrix(38,25) = (groebnerMatrix(8,25)/(groebnerMatrix(8,0))-groebnerMatrix(9,25)/(groebnerMatrix(9,0))); groebnerMatrix(38,26) = (groebnerMatrix(8,26)/(groebnerMatrix(8,0))-groebnerMatrix(9,26)/(groebnerMatrix(9,0))); groebnerMatrix(38,27) = (groebnerMatrix(8,27)/(groebnerMatrix(8,0))-groebnerMatrix(9,27)/(groebnerMatrix(9,0))); groebnerMatrix(38,28) = (groebnerMatrix(8,28)/(groebnerMatrix(8,0))-groebnerMatrix(9,28)/(groebnerMatrix(9,0))); groebnerMatrix(38,29) = (groebnerMatrix(8,29)/(groebnerMatrix(8,0))-groebnerMatrix(9,29)/(groebnerMatrix(9,0))); groebnerMatrix(38,30) = (groebnerMatrix(8,30)/(groebnerMatrix(8,0))-groebnerMatrix(9,30)/(groebnerMatrix(9,0))); groebnerMatrix(38,33) = (groebnerMatrix(8,33)/(groebnerMatrix(8,0))-groebnerMatrix(9,33)/(groebnerMatrix(9,0))); groebnerMatrix(38,34) = (groebnerMatrix(8,34)/(groebnerMatrix(8,0))-groebnerMatrix(9,34)/(groebnerMatrix(9,0))); groebnerMatrix(38,39) = (groebnerMatrix(8,39)/(groebnerMatrix(8,0))-groebnerMatrix(9,39)/(groebnerMatrix(9,0))); groebnerMatrix(38,40) = (groebnerMatrix(8,40)/(groebnerMatrix(8,0))-groebnerMatrix(9,40)/(groebnerMatrix(9,0))); groebnerMatrix(38,41) = (groebnerMatrix(8,41)/(groebnerMatrix(8,0))-groebnerMatrix(9,41)/(groebnerMatrix(9,0))); groebnerMatrix(38,42) = (groebnerMatrix(8,42)/(groebnerMatrix(8,0))-groebnerMatrix(9,42)/(groebnerMatrix(9,0))); groebnerMatrix(38,43) = (groebnerMatrix(8,43)/(groebnerMatrix(8,0))-groebnerMatrix(9,43)/(groebnerMatrix(9,0))); groebnerMatrix(38,44) = (groebnerMatrix(8,44)/(groebnerMatrix(8,0))-groebnerMatrix(9,44)/(groebnerMatrix(9,0))); groebnerMatrix(38,45) = (groebnerMatrix(8,45)/(groebnerMatrix(8,0))-groebnerMatrix(9,45)/(groebnerMatrix(9,0))); groebnerMatrix(38,46) = (groebnerMatrix(8,46)/(groebnerMatrix(8,0))-groebnerMatrix(9,46)/(groebnerMatrix(9,0))); groebnerMatrix(38,47) = (groebnerMatrix(8,47)/(groebnerMatrix(8,0))-groebnerMatrix(9,47)/(groebnerMatrix(9,0))); groebnerMatrix(38,48) = (groebnerMatrix(8,48)/(groebnerMatrix(8,0))-groebnerMatrix(9,48)/(groebnerMatrix(9,0))); groebnerMatrix(38,49) = (groebnerMatrix(8,49)/(groebnerMatrix(8,0))-groebnerMatrix(9,49)/(groebnerMatrix(9,0))); groebnerMatrix(38,50) = (groebnerMatrix(8,50)/(groebnerMatrix(8,0))-groebnerMatrix(9,50)/(groebnerMatrix(9,0))); groebnerMatrix(38,51) = (groebnerMatrix(8,51)/(groebnerMatrix(8,0))-groebnerMatrix(9,51)/(groebnerMatrix(9,0))); groebnerMatrix(38,52) = (groebnerMatrix(8,52)/(groebnerMatrix(8,0))-groebnerMatrix(9,52)/(groebnerMatrix(9,0))); groebnerMatrix(38,53) = (groebnerMatrix(8,53)/(groebnerMatrix(8,0))-groebnerMatrix(9,53)/(groebnerMatrix(9,0))); groebnerMatrix(38,54) = (groebnerMatrix(8,54)/(groebnerMatrix(8,0))-groebnerMatrix(9,54)/(groebnerMatrix(9,0))); groebnerMatrix(38,55) = (groebnerMatrix(8,55)/(groebnerMatrix(8,0))-groebnerMatrix(9,55)/(groebnerMatrix(9,0))); groebnerMatrix(38,56) = (groebnerMatrix(8,56)/(groebnerMatrix(8,0))-groebnerMatrix(9,56)/(groebnerMatrix(9,0))); groebnerMatrix(38,57) = (groebnerMatrix(8,57)/(groebnerMatrix(8,0))-groebnerMatrix(9,57)/(groebnerMatrix(9,0))); groebnerMatrix(38,58) = (groebnerMatrix(8,58)/(groebnerMatrix(8,0))-groebnerMatrix(9,58)/(groebnerMatrix(9,0))); groebnerMatrix(38,59) = (groebnerMatrix(8,59)/(groebnerMatrix(8,0))-groebnerMatrix(9,59)/(groebnerMatrix(9,0))); groebnerMatrix(38,60) = (groebnerMatrix(8,60)/(groebnerMatrix(8,0))-groebnerMatrix(9,60)/(groebnerMatrix(9,0))); groebnerMatrix(38,61) = (groebnerMatrix(8,61)/(groebnerMatrix(8,0))-groebnerMatrix(9,61)/(groebnerMatrix(9,0))); groebnerMatrix(38,62) = (groebnerMatrix(8,62)/(groebnerMatrix(8,0))-groebnerMatrix(9,62)/(groebnerMatrix(9,0))); groebnerMatrix(38,64) = (groebnerMatrix(8,64)/(groebnerMatrix(8,0))-groebnerMatrix(9,64)/(groebnerMatrix(9,0))); groebnerMatrix(38,65) = (groebnerMatrix(8,65)/(groebnerMatrix(8,0))-groebnerMatrix(9,65)/(groebnerMatrix(9,0))); groebnerMatrix(38,66) = (groebnerMatrix(8,66)/(groebnerMatrix(8,0))-groebnerMatrix(9,66)/(groebnerMatrix(9,0))); groebnerMatrix(38,67) = (groebnerMatrix(8,67)/(groebnerMatrix(8,0))-groebnerMatrix(9,67)/(groebnerMatrix(9,0))); groebnerMatrix(38,68) = (groebnerMatrix(8,68)/(groebnerMatrix(8,0))-groebnerMatrix(9,68)/(groebnerMatrix(9,0))); groebnerMatrix(38,69) = (groebnerMatrix(8,69)/(groebnerMatrix(8,0))-groebnerMatrix(9,69)/(groebnerMatrix(9,0))); groebnerMatrix(38,70) = (groebnerMatrix(8,70)/(groebnerMatrix(8,0))-groebnerMatrix(9,70)/(groebnerMatrix(9,0))); groebnerMatrix(38,71) = (groebnerMatrix(8,71)/(groebnerMatrix(8,0))-groebnerMatrix(9,71)/(groebnerMatrix(9,0))); groebnerMatrix(38,73) = (groebnerMatrix(8,73)/(groebnerMatrix(8,0))-groebnerMatrix(9,73)/(groebnerMatrix(9,0))); groebnerMatrix(38,74) = (groebnerMatrix(8,74)/(groebnerMatrix(8,0))-groebnerMatrix(9,74)/(groebnerMatrix(9,0))); groebnerMatrix(38,76) = (groebnerMatrix(8,76)/(groebnerMatrix(8,0))-groebnerMatrix(9,76)/(groebnerMatrix(9,0))); groebnerMatrix(38,77) = (groebnerMatrix(8,77)/(groebnerMatrix(8,0))-groebnerMatrix(9,77)/(groebnerMatrix(9,0))); groebnerMatrix(38,78) = (groebnerMatrix(8,78)/(groebnerMatrix(8,0))-groebnerMatrix(9,78)/(groebnerMatrix(9,0))); groebnerMatrix(38,79) = (groebnerMatrix(8,79)/(groebnerMatrix(8,0))-groebnerMatrix(9,79)/(groebnerMatrix(9,0))); groebnerMatrix(38,80) = (groebnerMatrix(8,80)/(groebnerMatrix(8,0))-groebnerMatrix(9,80)/(groebnerMatrix(9,0))); groebnerMatrix(38,81) = (groebnerMatrix(8,81)/(groebnerMatrix(8,0))-groebnerMatrix(9,81)/(groebnerMatrix(9,0))); groebnerMatrix(38,82) = (groebnerMatrix(8,82)/(groebnerMatrix(8,0))-groebnerMatrix(9,82)/(groebnerMatrix(9,0))); groebnerMatrix(38,83) = (groebnerMatrix(8,83)/(groebnerMatrix(8,0))-groebnerMatrix(9,83)/(groebnerMatrix(9,0))); groebnerMatrix(38,84) = (groebnerMatrix(8,84)/(groebnerMatrix(8,0))-groebnerMatrix(9,84)/(groebnerMatrix(9,0))); groebnerMatrix(38,85) = (groebnerMatrix(8,85)/(groebnerMatrix(8,0))-groebnerMatrix(9,85)/(groebnerMatrix(9,0))); groebnerMatrix(38,86) = (groebnerMatrix(8,86)/(groebnerMatrix(8,0))-groebnerMatrix(9,86)/(groebnerMatrix(9,0))); groebnerMatrix(38,87) = (groebnerMatrix(8,87)/(groebnerMatrix(8,0))-groebnerMatrix(9,87)/(groebnerMatrix(9,0))); groebnerMatrix(38,89) = (groebnerMatrix(8,89)/(groebnerMatrix(8,0))-groebnerMatrix(9,89)/(groebnerMatrix(9,0))); groebnerMatrix(38,91) = (groebnerMatrix(8,91)/(groebnerMatrix(8,0))-groebnerMatrix(9,91)/(groebnerMatrix(9,0))); groebnerMatrix(38,92) = (groebnerMatrix(8,92)/(groebnerMatrix(8,0))-groebnerMatrix(9,92)/(groebnerMatrix(9,0))); groebnerMatrix(38,94) = (groebnerMatrix(8,94)/(groebnerMatrix(8,0))-groebnerMatrix(9,94)/(groebnerMatrix(9,0))); groebnerMatrix(38,97) = (groebnerMatrix(8,97)/(groebnerMatrix(8,0))-groebnerMatrix(9,97)/(groebnerMatrix(9,0))); groebnerMatrix(38,98) = (groebnerMatrix(8,98)/(groebnerMatrix(8,0))-groebnerMatrix(9,98)/(groebnerMatrix(9,0))); groebnerMatrix(38,99) = (groebnerMatrix(8,99)/(groebnerMatrix(8,0))-groebnerMatrix(9,99)/(groebnerMatrix(9,0))); groebnerMatrix(38,100) = (groebnerMatrix(8,100)/(groebnerMatrix(8,0))-groebnerMatrix(9,100)/(groebnerMatrix(9,0))); groebnerMatrix(38,101) = (groebnerMatrix(8,101)/(groebnerMatrix(8,0))-groebnerMatrix(9,101)/(groebnerMatrix(9,0))); groebnerMatrix(38,103) = (groebnerMatrix(8,103)/(groebnerMatrix(8,0))-groebnerMatrix(9,103)/(groebnerMatrix(9,0))); groebnerMatrix(38,104) = (groebnerMatrix(8,104)/(groebnerMatrix(8,0))-groebnerMatrix(9,104)/(groebnerMatrix(9,0))); groebnerMatrix(38,105) = (groebnerMatrix(8,105)/(groebnerMatrix(8,0))-groebnerMatrix(9,105)/(groebnerMatrix(9,0))); groebnerMatrix(38,106) = (groebnerMatrix(8,106)/(groebnerMatrix(8,0))-groebnerMatrix(9,106)/(groebnerMatrix(9,0))); groebnerMatrix(38,107) = (groebnerMatrix(8,107)/(groebnerMatrix(8,0))-groebnerMatrix(9,107)/(groebnerMatrix(9,0))); groebnerMatrix(38,108) = (groebnerMatrix(8,108)/(groebnerMatrix(8,0))-groebnerMatrix(9,108)/(groebnerMatrix(9,0))); groebnerMatrix(38,109) = (groebnerMatrix(8,109)/(groebnerMatrix(8,0))-groebnerMatrix(9,109)/(groebnerMatrix(9,0))); groebnerMatrix(38,110) = (groebnerMatrix(8,110)/(groebnerMatrix(8,0))-groebnerMatrix(9,110)/(groebnerMatrix(9,0))); groebnerMatrix(38,111) = (groebnerMatrix(8,111)/(groebnerMatrix(8,0))-groebnerMatrix(9,111)/(groebnerMatrix(9,0))); groebnerMatrix(38,112) = (groebnerMatrix(8,112)/(groebnerMatrix(8,0))-groebnerMatrix(9,112)/(groebnerMatrix(9,0))); groebnerMatrix(38,113) = (groebnerMatrix(8,113)/(groebnerMatrix(8,0))-groebnerMatrix(9,113)/(groebnerMatrix(9,0))); groebnerMatrix(38,115) = (groebnerMatrix(8,115)/(groebnerMatrix(8,0))-groebnerMatrix(9,115)/(groebnerMatrix(9,0))); groebnerMatrix(38,116) = (groebnerMatrix(8,116)/(groebnerMatrix(8,0))-groebnerMatrix(9,116)/(groebnerMatrix(9,0))); groebnerMatrix(38,118) = (groebnerMatrix(8,118)/(groebnerMatrix(8,0))-groebnerMatrix(9,118)/(groebnerMatrix(9,0))); groebnerMatrix(38,119) = (groebnerMatrix(8,119)/(groebnerMatrix(8,0))-groebnerMatrix(9,119)/(groebnerMatrix(9,0))); groebnerMatrix(38,120) = (groebnerMatrix(8,120)/(groebnerMatrix(8,0))-groebnerMatrix(9,120)/(groebnerMatrix(9,0))); groebnerMatrix(38,121) = (groebnerMatrix(8,121)/(groebnerMatrix(8,0))-groebnerMatrix(9,121)/(groebnerMatrix(9,0))); groebnerMatrix(38,122) = (groebnerMatrix(8,122)/(groebnerMatrix(8,0))-groebnerMatrix(9,122)/(groebnerMatrix(9,0))); groebnerMatrix(38,123) = (groebnerMatrix(8,123)/(groebnerMatrix(8,0))-groebnerMatrix(9,123)/(groebnerMatrix(9,0))); groebnerMatrix(38,125) = (groebnerMatrix(8,125)/(groebnerMatrix(8,0))-groebnerMatrix(9,125)/(groebnerMatrix(9,0))); groebnerMatrix(38,126) = (groebnerMatrix(8,126)/(groebnerMatrix(8,0))-groebnerMatrix(9,126)/(groebnerMatrix(9,0))); groebnerMatrix(38,127) = (groebnerMatrix(8,127)/(groebnerMatrix(8,0))-groebnerMatrix(9,127)/(groebnerMatrix(9,0))); groebnerMatrix(38,128) = (groebnerMatrix(8,128)/(groebnerMatrix(8,0))-groebnerMatrix(9,128)/(groebnerMatrix(9,0))); groebnerMatrix(38,129) = (groebnerMatrix(8,129)/(groebnerMatrix(8,0))-groebnerMatrix(9,129)/(groebnerMatrix(9,0))); groebnerMatrix(38,130) = (groebnerMatrix(8,130)/(groebnerMatrix(8,0))-groebnerMatrix(9,130)/(groebnerMatrix(9,0))); groebnerMatrix(38,133) = (groebnerMatrix(8,133)/(groebnerMatrix(8,0))-groebnerMatrix(9,133)/(groebnerMatrix(9,0))); groebnerMatrix(38,134) = (groebnerMatrix(8,134)/(groebnerMatrix(8,0))-groebnerMatrix(9,134)/(groebnerMatrix(9,0))); groebnerMatrix(38,136) = (groebnerMatrix(8,136)/(groebnerMatrix(8,0))-groebnerMatrix(9,136)/(groebnerMatrix(9,0))); groebnerMatrix(38,137) = (groebnerMatrix(8,137)/(groebnerMatrix(8,0))-groebnerMatrix(9,137)/(groebnerMatrix(9,0))); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial39( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(39,1) = groebnerMatrix(9,1)/(groebnerMatrix(9,0)); groebnerMatrix(39,2) = groebnerMatrix(9,2)/(groebnerMatrix(9,0)); groebnerMatrix(39,3) = groebnerMatrix(9,3)/(groebnerMatrix(9,0)); groebnerMatrix(39,4) = groebnerMatrix(9,4)/(groebnerMatrix(9,0)); groebnerMatrix(39,5) = groebnerMatrix(9,5)/(groebnerMatrix(9,0)); groebnerMatrix(39,6) = groebnerMatrix(9,6)/(groebnerMatrix(9,0)); groebnerMatrix(39,7) = groebnerMatrix(9,7)/(groebnerMatrix(9,0)); groebnerMatrix(39,8) = groebnerMatrix(9,8)/(groebnerMatrix(9,0)); groebnerMatrix(39,9) = -groebnerMatrix(14,153)/(groebnerMatrix(14,148)); groebnerMatrix(39,10) = groebnerMatrix(9,10)/(groebnerMatrix(9,0)); groebnerMatrix(39,11) = groebnerMatrix(9,11)/(groebnerMatrix(9,0)); groebnerMatrix(39,12) = groebnerMatrix(9,12)/(groebnerMatrix(9,0)); groebnerMatrix(39,13) = groebnerMatrix(9,13)/(groebnerMatrix(9,0)); groebnerMatrix(39,14) = groebnerMatrix(9,14)/(groebnerMatrix(9,0)); groebnerMatrix(39,15) = groebnerMatrix(9,15)/(groebnerMatrix(9,0)); groebnerMatrix(39,16) = groebnerMatrix(9,16)/(groebnerMatrix(9,0)); groebnerMatrix(39,18) = groebnerMatrix(9,18)/(groebnerMatrix(9,0)); groebnerMatrix(39,19) = groebnerMatrix(9,19)/(groebnerMatrix(9,0)); groebnerMatrix(39,20) = groebnerMatrix(9,20)/(groebnerMatrix(9,0)); groebnerMatrix(39,21) = groebnerMatrix(9,21)/(groebnerMatrix(9,0)); groebnerMatrix(39,22) = groebnerMatrix(9,22)/(groebnerMatrix(9,0)); groebnerMatrix(39,23) = (groebnerMatrix(9,23)/(groebnerMatrix(9,0))-groebnerMatrix(14,159)/(groebnerMatrix(14,148))); groebnerMatrix(39,25) = groebnerMatrix(9,25)/(groebnerMatrix(9,0)); groebnerMatrix(39,26) = groebnerMatrix(9,26)/(groebnerMatrix(9,0)); groebnerMatrix(39,27) = groebnerMatrix(9,27)/(groebnerMatrix(9,0)); groebnerMatrix(39,28) = groebnerMatrix(9,28)/(groebnerMatrix(9,0)); groebnerMatrix(39,29) = groebnerMatrix(9,29)/(groebnerMatrix(9,0)); groebnerMatrix(39,30) = groebnerMatrix(9,30)/(groebnerMatrix(9,0)); groebnerMatrix(39,33) = groebnerMatrix(9,33)/(groebnerMatrix(9,0)); groebnerMatrix(39,34) = groebnerMatrix(9,34)/(groebnerMatrix(9,0)); groebnerMatrix(39,39) = groebnerMatrix(9,39)/(groebnerMatrix(9,0)); groebnerMatrix(39,40) = groebnerMatrix(9,40)/(groebnerMatrix(9,0)); groebnerMatrix(39,41) = groebnerMatrix(9,41)/(groebnerMatrix(9,0)); groebnerMatrix(39,42) = groebnerMatrix(9,42)/(groebnerMatrix(9,0)); groebnerMatrix(39,43) = groebnerMatrix(9,43)/(groebnerMatrix(9,0)); groebnerMatrix(39,44) = groebnerMatrix(9,44)/(groebnerMatrix(9,0)); groebnerMatrix(39,45) = groebnerMatrix(9,45)/(groebnerMatrix(9,0)); groebnerMatrix(39,46) = groebnerMatrix(9,46)/(groebnerMatrix(9,0)); groebnerMatrix(39,47) = groebnerMatrix(9,47)/(groebnerMatrix(9,0)); groebnerMatrix(39,48) = groebnerMatrix(9,48)/(groebnerMatrix(9,0)); groebnerMatrix(39,49) = groebnerMatrix(9,49)/(groebnerMatrix(9,0)); groebnerMatrix(39,50) = groebnerMatrix(9,50)/(groebnerMatrix(9,0)); groebnerMatrix(39,51) = groebnerMatrix(9,51)/(groebnerMatrix(9,0)); groebnerMatrix(39,52) = groebnerMatrix(9,52)/(groebnerMatrix(9,0)); groebnerMatrix(39,53) = groebnerMatrix(9,53)/(groebnerMatrix(9,0)); groebnerMatrix(39,54) = groebnerMatrix(9,54)/(groebnerMatrix(9,0)); groebnerMatrix(39,55) = groebnerMatrix(9,55)/(groebnerMatrix(9,0)); groebnerMatrix(39,56) = groebnerMatrix(9,56)/(groebnerMatrix(9,0)); groebnerMatrix(39,57) = groebnerMatrix(9,57)/(groebnerMatrix(9,0)); groebnerMatrix(39,58) = groebnerMatrix(9,58)/(groebnerMatrix(9,0)); groebnerMatrix(39,59) = groebnerMatrix(9,59)/(groebnerMatrix(9,0)); groebnerMatrix(39,60) = groebnerMatrix(9,60)/(groebnerMatrix(9,0)); groebnerMatrix(39,61) = groebnerMatrix(9,61)/(groebnerMatrix(9,0)); groebnerMatrix(39,62) = groebnerMatrix(9,62)/(groebnerMatrix(9,0)); groebnerMatrix(39,64) = groebnerMatrix(9,64)/(groebnerMatrix(9,0)); groebnerMatrix(39,65) = groebnerMatrix(9,65)/(groebnerMatrix(9,0)); groebnerMatrix(39,66) = groebnerMatrix(9,66)/(groebnerMatrix(9,0)); groebnerMatrix(39,67) = groebnerMatrix(9,67)/(groebnerMatrix(9,0)); groebnerMatrix(39,68) = groebnerMatrix(9,68)/(groebnerMatrix(9,0)); groebnerMatrix(39,69) = groebnerMatrix(9,69)/(groebnerMatrix(9,0)); groebnerMatrix(39,70) = groebnerMatrix(9,70)/(groebnerMatrix(9,0)); groebnerMatrix(39,71) = groebnerMatrix(9,71)/(groebnerMatrix(9,0)); groebnerMatrix(39,73) = groebnerMatrix(9,73)/(groebnerMatrix(9,0)); groebnerMatrix(39,74) = groebnerMatrix(9,74)/(groebnerMatrix(9,0)); groebnerMatrix(39,76) = groebnerMatrix(9,76)/(groebnerMatrix(9,0)); groebnerMatrix(39,77) = groebnerMatrix(9,77)/(groebnerMatrix(9,0)); groebnerMatrix(39,78) = groebnerMatrix(9,78)/(groebnerMatrix(9,0)); groebnerMatrix(39,79) = groebnerMatrix(9,79)/(groebnerMatrix(9,0)); groebnerMatrix(39,80) = groebnerMatrix(9,80)/(groebnerMatrix(9,0)); groebnerMatrix(39,81) = groebnerMatrix(9,81)/(groebnerMatrix(9,0)); groebnerMatrix(39,82) = groebnerMatrix(9,82)/(groebnerMatrix(9,0)); groebnerMatrix(39,83) = groebnerMatrix(9,83)/(groebnerMatrix(9,0)); groebnerMatrix(39,84) = groebnerMatrix(9,84)/(groebnerMatrix(9,0)); groebnerMatrix(39,85) = groebnerMatrix(9,85)/(groebnerMatrix(9,0)); groebnerMatrix(39,86) = groebnerMatrix(9,86)/(groebnerMatrix(9,0)); groebnerMatrix(39,87) = groebnerMatrix(9,87)/(groebnerMatrix(9,0)); groebnerMatrix(39,89) = groebnerMatrix(9,89)/(groebnerMatrix(9,0)); groebnerMatrix(39,91) = groebnerMatrix(9,91)/(groebnerMatrix(9,0)); groebnerMatrix(39,92) = groebnerMatrix(9,92)/(groebnerMatrix(9,0)); groebnerMatrix(39,94) = groebnerMatrix(9,94)/(groebnerMatrix(9,0)); groebnerMatrix(39,97) = groebnerMatrix(9,97)/(groebnerMatrix(9,0)); groebnerMatrix(39,98) = groebnerMatrix(9,98)/(groebnerMatrix(9,0)); groebnerMatrix(39,99) = groebnerMatrix(9,99)/(groebnerMatrix(9,0)); groebnerMatrix(39,100) = groebnerMatrix(9,100)/(groebnerMatrix(9,0)); groebnerMatrix(39,101) = groebnerMatrix(9,101)/(groebnerMatrix(9,0)); groebnerMatrix(39,103) = groebnerMatrix(9,103)/(groebnerMatrix(9,0)); groebnerMatrix(39,104) = groebnerMatrix(9,104)/(groebnerMatrix(9,0)); groebnerMatrix(39,105) = groebnerMatrix(9,105)/(groebnerMatrix(9,0)); groebnerMatrix(39,106) = groebnerMatrix(9,106)/(groebnerMatrix(9,0)); groebnerMatrix(39,107) = groebnerMatrix(9,107)/(groebnerMatrix(9,0)); groebnerMatrix(39,108) = groebnerMatrix(9,108)/(groebnerMatrix(9,0)); groebnerMatrix(39,109) = groebnerMatrix(9,109)/(groebnerMatrix(9,0)); groebnerMatrix(39,110) = groebnerMatrix(9,110)/(groebnerMatrix(9,0)); groebnerMatrix(39,111) = groebnerMatrix(9,111)/(groebnerMatrix(9,0)); groebnerMatrix(39,112) = groebnerMatrix(9,112)/(groebnerMatrix(9,0)); groebnerMatrix(39,113) = groebnerMatrix(9,113)/(groebnerMatrix(9,0)); groebnerMatrix(39,115) = groebnerMatrix(9,115)/(groebnerMatrix(9,0)); groebnerMatrix(39,116) = groebnerMatrix(9,116)/(groebnerMatrix(9,0)); groebnerMatrix(39,118) = groebnerMatrix(9,118)/(groebnerMatrix(9,0)); groebnerMatrix(39,119) = groebnerMatrix(9,119)/(groebnerMatrix(9,0)); groebnerMatrix(39,120) = groebnerMatrix(9,120)/(groebnerMatrix(9,0)); groebnerMatrix(39,121) = groebnerMatrix(9,121)/(groebnerMatrix(9,0)); groebnerMatrix(39,122) = groebnerMatrix(9,122)/(groebnerMatrix(9,0)); groebnerMatrix(39,123) = groebnerMatrix(9,123)/(groebnerMatrix(9,0)); groebnerMatrix(39,125) = groebnerMatrix(9,125)/(groebnerMatrix(9,0)); groebnerMatrix(39,126) = groebnerMatrix(9,126)/(groebnerMatrix(9,0)); groebnerMatrix(39,127) = groebnerMatrix(9,127)/(groebnerMatrix(9,0)); groebnerMatrix(39,128) = groebnerMatrix(9,128)/(groebnerMatrix(9,0)); groebnerMatrix(39,129) = groebnerMatrix(9,129)/(groebnerMatrix(9,0)); groebnerMatrix(39,130) = groebnerMatrix(9,130)/(groebnerMatrix(9,0)); groebnerMatrix(39,133) = groebnerMatrix(9,133)/(groebnerMatrix(9,0)); groebnerMatrix(39,134) = groebnerMatrix(9,134)/(groebnerMatrix(9,0)); groebnerMatrix(39,136) = groebnerMatrix(9,136)/(groebnerMatrix(9,0)); groebnerMatrix(39,137) = groebnerMatrix(9,137)/(groebnerMatrix(9,0)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial40( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(40,89) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(40,90) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(40,92) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(40,93) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(40,95) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(40,96) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(40,116) = groebnerMatrix(18,182)/(groebnerMatrix(18,175)); groebnerMatrix(40,125) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(40,126) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(40,127) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(40,128) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(40,129) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(40,130) = -groebnerMatrix(39,183)/(groebnerMatrix(39,162)); groebnerMatrix(40,131) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(40,132) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(40,140) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(40,157) = groebnerMatrix(18,187)/(groebnerMatrix(18,175)); groebnerMatrix(40,170) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(40,171) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(40,172) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(40,173) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(40,174) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(40,175) = -groebnerMatrix(39,192)/(groebnerMatrix(39,162)); groebnerMatrix(40,176) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(40,177) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(40,185) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(40,194) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial41( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(41,81) = -groebnerMatrix(38,162)/(groebnerMatrix(38,161)); groebnerMatrix(41,89) = -groebnerMatrix(38,170)/(groebnerMatrix(38,161)); groebnerMatrix(41,90) = -groebnerMatrix(38,171)/(groebnerMatrix(38,161)); groebnerMatrix(41,92) = -groebnerMatrix(38,173)/(groebnerMatrix(38,161)); groebnerMatrix(41,93) = -groebnerMatrix(38,174)/(groebnerMatrix(38,161)); groebnerMatrix(41,95) = -groebnerMatrix(38,176)/(groebnerMatrix(38,161)); groebnerMatrix(41,96) = -groebnerMatrix(38,177)/(groebnerMatrix(38,161)); groebnerMatrix(41,111) = groebnerMatrix(18,182)/(groebnerMatrix(18,175)); groebnerMatrix(41,125) = -groebnerMatrix(38,178)/(groebnerMatrix(38,161)); groebnerMatrix(41,126) = -groebnerMatrix(38,179)/(groebnerMatrix(38,161)); groebnerMatrix(41,127) = -groebnerMatrix(38,180)/(groebnerMatrix(38,161)); groebnerMatrix(41,128) = -groebnerMatrix(38,181)/(groebnerMatrix(38,161)); groebnerMatrix(41,129) = -groebnerMatrix(38,182)/(groebnerMatrix(38,161)); groebnerMatrix(41,130) = -groebnerMatrix(38,183)/(groebnerMatrix(38,161)); groebnerMatrix(41,131) = -groebnerMatrix(38,184)/(groebnerMatrix(38,161)); groebnerMatrix(41,132) = -groebnerMatrix(38,185)/(groebnerMatrix(38,161)); groebnerMatrix(41,140) = -groebnerMatrix(38,186)/(groebnerMatrix(38,161)); groebnerMatrix(41,152) = groebnerMatrix(18,187)/(groebnerMatrix(18,175)); groebnerMatrix(41,170) = -groebnerMatrix(38,187)/(groebnerMatrix(38,161)); groebnerMatrix(41,171) = -groebnerMatrix(38,188)/(groebnerMatrix(38,161)); groebnerMatrix(41,172) = -groebnerMatrix(38,189)/(groebnerMatrix(38,161)); groebnerMatrix(41,173) = -groebnerMatrix(38,190)/(groebnerMatrix(38,161)); groebnerMatrix(41,174) = -groebnerMatrix(38,191)/(groebnerMatrix(38,161)); groebnerMatrix(41,175) = -groebnerMatrix(38,192)/(groebnerMatrix(38,161)); groebnerMatrix(41,176) = -groebnerMatrix(38,193)/(groebnerMatrix(38,161)); groebnerMatrix(41,177) = -groebnerMatrix(38,194)/(groebnerMatrix(38,161)); groebnerMatrix(41,185) = -groebnerMatrix(38,195)/(groebnerMatrix(38,161)); groebnerMatrix(41,194) = -groebnerMatrix(38,196)/(groebnerMatrix(38,161)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial42( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(42,80) = -groebnerMatrix(37,161)/(groebnerMatrix(37,160)); groebnerMatrix(42,81) = -groebnerMatrix(37,162)/(groebnerMatrix(37,160)); groebnerMatrix(42,89) = -groebnerMatrix(37,170)/(groebnerMatrix(37,160)); groebnerMatrix(42,90) = -groebnerMatrix(37,171)/(groebnerMatrix(37,160)); groebnerMatrix(42,92) = -groebnerMatrix(37,173)/(groebnerMatrix(37,160)); groebnerMatrix(42,93) = -groebnerMatrix(37,174)/(groebnerMatrix(37,160)); groebnerMatrix(42,95) = -groebnerMatrix(37,176)/(groebnerMatrix(37,160)); groebnerMatrix(42,96) = -groebnerMatrix(37,177)/(groebnerMatrix(37,160)); groebnerMatrix(42,110) = groebnerMatrix(18,182)/(groebnerMatrix(18,175)); groebnerMatrix(42,125) = -groebnerMatrix(37,178)/(groebnerMatrix(37,160)); groebnerMatrix(42,126) = -groebnerMatrix(37,179)/(groebnerMatrix(37,160)); groebnerMatrix(42,127) = -groebnerMatrix(37,180)/(groebnerMatrix(37,160)); groebnerMatrix(42,128) = -groebnerMatrix(37,181)/(groebnerMatrix(37,160)); groebnerMatrix(42,129) = -groebnerMatrix(37,182)/(groebnerMatrix(37,160)); groebnerMatrix(42,130) = -groebnerMatrix(37,183)/(groebnerMatrix(37,160)); groebnerMatrix(42,131) = -groebnerMatrix(37,184)/(groebnerMatrix(37,160)); groebnerMatrix(42,132) = -groebnerMatrix(37,185)/(groebnerMatrix(37,160)); groebnerMatrix(42,140) = -groebnerMatrix(37,186)/(groebnerMatrix(37,160)); groebnerMatrix(42,148) = groebnerMatrix(18,187)/(groebnerMatrix(18,175)); groebnerMatrix(42,170) = -groebnerMatrix(37,187)/(groebnerMatrix(37,160)); groebnerMatrix(42,171) = -groebnerMatrix(37,188)/(groebnerMatrix(37,160)); groebnerMatrix(42,172) = -groebnerMatrix(37,189)/(groebnerMatrix(37,160)); groebnerMatrix(42,173) = -groebnerMatrix(37,190)/(groebnerMatrix(37,160)); groebnerMatrix(42,174) = -groebnerMatrix(37,191)/(groebnerMatrix(37,160)); groebnerMatrix(42,175) = -groebnerMatrix(37,192)/(groebnerMatrix(37,160)); groebnerMatrix(42,176) = -groebnerMatrix(37,193)/(groebnerMatrix(37,160)); groebnerMatrix(42,177) = -groebnerMatrix(37,194)/(groebnerMatrix(37,160)); groebnerMatrix(42,185) = -groebnerMatrix(37,195)/(groebnerMatrix(37,160)); groebnerMatrix(42,194) = -groebnerMatrix(37,196)/(groebnerMatrix(37,160)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial43( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(43,79) = -groebnerMatrix(36,160)/(groebnerMatrix(36,159)); groebnerMatrix(43,80) = -groebnerMatrix(36,161)/(groebnerMatrix(36,159)); groebnerMatrix(43,81) = -groebnerMatrix(36,162)/(groebnerMatrix(36,159)); groebnerMatrix(43,89) = -groebnerMatrix(36,170)/(groebnerMatrix(36,159)); groebnerMatrix(43,90) = -groebnerMatrix(36,171)/(groebnerMatrix(36,159)); groebnerMatrix(43,92) = -groebnerMatrix(36,173)/(groebnerMatrix(36,159)); groebnerMatrix(43,93) = -groebnerMatrix(36,174)/(groebnerMatrix(36,159)); groebnerMatrix(43,95) = -groebnerMatrix(36,176)/(groebnerMatrix(36,159)); groebnerMatrix(43,96) = -groebnerMatrix(36,177)/(groebnerMatrix(36,159)); groebnerMatrix(43,113) = groebnerMatrix(17,179)/(groebnerMatrix(17,172)); groebnerMatrix(43,125) = -groebnerMatrix(36,178)/(groebnerMatrix(36,159)); groebnerMatrix(43,126) = -groebnerMatrix(36,179)/(groebnerMatrix(36,159)); groebnerMatrix(43,127) = -groebnerMatrix(36,180)/(groebnerMatrix(36,159)); groebnerMatrix(43,128) = -groebnerMatrix(36,181)/(groebnerMatrix(36,159)); groebnerMatrix(43,129) = -groebnerMatrix(36,182)/(groebnerMatrix(36,159)); groebnerMatrix(43,130) = -groebnerMatrix(36,183)/(groebnerMatrix(36,159)); groebnerMatrix(43,131) = -groebnerMatrix(36,184)/(groebnerMatrix(36,159)); groebnerMatrix(43,132) = -groebnerMatrix(36,185)/(groebnerMatrix(36,159)); groebnerMatrix(43,140) = -groebnerMatrix(36,186)/(groebnerMatrix(36,159)); groebnerMatrix(43,160) = groebnerMatrix(17,190)/(groebnerMatrix(17,172)); groebnerMatrix(43,170) = -groebnerMatrix(36,187)/(groebnerMatrix(36,159)); groebnerMatrix(43,171) = -groebnerMatrix(36,188)/(groebnerMatrix(36,159)); groebnerMatrix(43,172) = -groebnerMatrix(36,189)/(groebnerMatrix(36,159)); groebnerMatrix(43,173) = -groebnerMatrix(36,190)/(groebnerMatrix(36,159)); groebnerMatrix(43,174) = -groebnerMatrix(36,191)/(groebnerMatrix(36,159)); groebnerMatrix(43,175) = -groebnerMatrix(36,192)/(groebnerMatrix(36,159)); groebnerMatrix(43,176) = -groebnerMatrix(36,193)/(groebnerMatrix(36,159)); groebnerMatrix(43,177) = -groebnerMatrix(36,194)/(groebnerMatrix(36,159)); groebnerMatrix(43,185) = -groebnerMatrix(36,195)/(groebnerMatrix(36,159)); groebnerMatrix(43,194) = -groebnerMatrix(36,196)/(groebnerMatrix(36,159)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial44( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(44,78) = -groebnerMatrix(35,159)/(groebnerMatrix(35,158)); groebnerMatrix(44,79) = -groebnerMatrix(35,160)/(groebnerMatrix(35,158)); groebnerMatrix(44,80) = -groebnerMatrix(35,161)/(groebnerMatrix(35,158)); groebnerMatrix(44,81) = -groebnerMatrix(35,162)/(groebnerMatrix(35,158)); groebnerMatrix(44,89) = -groebnerMatrix(35,170)/(groebnerMatrix(35,158)); groebnerMatrix(44,90) = -groebnerMatrix(35,171)/(groebnerMatrix(35,158)); groebnerMatrix(44,92) = -groebnerMatrix(35,173)/(groebnerMatrix(35,158)); groebnerMatrix(44,93) = -groebnerMatrix(35,174)/(groebnerMatrix(35,158)); groebnerMatrix(44,95) = -groebnerMatrix(35,176)/(groebnerMatrix(35,158)); groebnerMatrix(44,96) = -groebnerMatrix(35,177)/(groebnerMatrix(35,158)); groebnerMatrix(44,108) = groebnerMatrix(18,182)/(groebnerMatrix(18,175)); groebnerMatrix(44,125) = -groebnerMatrix(35,178)/(groebnerMatrix(35,158)); groebnerMatrix(44,126) = -groebnerMatrix(35,179)/(groebnerMatrix(35,158)); groebnerMatrix(44,127) = -groebnerMatrix(35,180)/(groebnerMatrix(35,158)); groebnerMatrix(44,128) = -groebnerMatrix(35,181)/(groebnerMatrix(35,158)); groebnerMatrix(44,129) = -groebnerMatrix(35,182)/(groebnerMatrix(35,158)); groebnerMatrix(44,130) = -groebnerMatrix(35,183)/(groebnerMatrix(35,158)); groebnerMatrix(44,131) = -groebnerMatrix(35,184)/(groebnerMatrix(35,158)); groebnerMatrix(44,132) = -groebnerMatrix(35,185)/(groebnerMatrix(35,158)); groebnerMatrix(44,140) = -groebnerMatrix(35,186)/(groebnerMatrix(35,158)); groebnerMatrix(44,143) = groebnerMatrix(18,187)/(groebnerMatrix(18,175)); groebnerMatrix(44,170) = -groebnerMatrix(35,187)/(groebnerMatrix(35,158)); groebnerMatrix(44,171) = -groebnerMatrix(35,188)/(groebnerMatrix(35,158)); groebnerMatrix(44,172) = -groebnerMatrix(35,189)/(groebnerMatrix(35,158)); groebnerMatrix(44,173) = -groebnerMatrix(35,190)/(groebnerMatrix(35,158)); groebnerMatrix(44,174) = -groebnerMatrix(35,191)/(groebnerMatrix(35,158)); groebnerMatrix(44,175) = -groebnerMatrix(35,192)/(groebnerMatrix(35,158)); groebnerMatrix(44,176) = -groebnerMatrix(35,193)/(groebnerMatrix(35,158)); groebnerMatrix(44,177) = -groebnerMatrix(35,194)/(groebnerMatrix(35,158)); groebnerMatrix(44,185) = -groebnerMatrix(35,195)/(groebnerMatrix(35,158)); groebnerMatrix(44,194) = -groebnerMatrix(35,196)/(groebnerMatrix(35,158)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial45( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(45,77) = -groebnerMatrix(34,158)/(groebnerMatrix(34,157)); groebnerMatrix(45,78) = -groebnerMatrix(34,159)/(groebnerMatrix(34,157)); groebnerMatrix(45,79) = -groebnerMatrix(34,160)/(groebnerMatrix(34,157)); groebnerMatrix(45,80) = -groebnerMatrix(34,161)/(groebnerMatrix(34,157)); groebnerMatrix(45,81) = -groebnerMatrix(34,162)/(groebnerMatrix(34,157)); groebnerMatrix(45,89) = -groebnerMatrix(34,170)/(groebnerMatrix(34,157)); groebnerMatrix(45,90) = -groebnerMatrix(34,171)/(groebnerMatrix(34,157)); groebnerMatrix(45,92) = -groebnerMatrix(34,173)/(groebnerMatrix(34,157)); groebnerMatrix(45,93) = -groebnerMatrix(34,174)/(groebnerMatrix(34,157)); groebnerMatrix(45,95) = -groebnerMatrix(34,176)/(groebnerMatrix(34,157)); groebnerMatrix(45,96) = -groebnerMatrix(34,177)/(groebnerMatrix(34,157)); groebnerMatrix(45,107) = groebnerMatrix(18,182)/(groebnerMatrix(18,175)); groebnerMatrix(45,125) = -groebnerMatrix(34,178)/(groebnerMatrix(34,157)); groebnerMatrix(45,126) = -groebnerMatrix(34,179)/(groebnerMatrix(34,157)); groebnerMatrix(45,127) = -groebnerMatrix(34,180)/(groebnerMatrix(34,157)); groebnerMatrix(45,128) = -groebnerMatrix(34,181)/(groebnerMatrix(34,157)); groebnerMatrix(45,129) = -groebnerMatrix(34,182)/(groebnerMatrix(34,157)); groebnerMatrix(45,130) = -groebnerMatrix(34,183)/(groebnerMatrix(34,157)); groebnerMatrix(45,131) = -groebnerMatrix(34,184)/(groebnerMatrix(34,157)); groebnerMatrix(45,132) = -groebnerMatrix(34,185)/(groebnerMatrix(34,157)); groebnerMatrix(45,140) = -groebnerMatrix(34,186)/(groebnerMatrix(34,157)); groebnerMatrix(45,142) = groebnerMatrix(18,187)/(groebnerMatrix(18,175)); groebnerMatrix(45,170) = -groebnerMatrix(34,187)/(groebnerMatrix(34,157)); groebnerMatrix(45,171) = -groebnerMatrix(34,188)/(groebnerMatrix(34,157)); groebnerMatrix(45,172) = -groebnerMatrix(34,189)/(groebnerMatrix(34,157)); groebnerMatrix(45,173) = -groebnerMatrix(34,190)/(groebnerMatrix(34,157)); groebnerMatrix(45,174) = -groebnerMatrix(34,191)/(groebnerMatrix(34,157)); groebnerMatrix(45,175) = -groebnerMatrix(34,192)/(groebnerMatrix(34,157)); groebnerMatrix(45,176) = -groebnerMatrix(34,193)/(groebnerMatrix(34,157)); groebnerMatrix(45,177) = -groebnerMatrix(34,194)/(groebnerMatrix(34,157)); groebnerMatrix(45,185) = -groebnerMatrix(34,195)/(groebnerMatrix(34,157)); groebnerMatrix(45,194) = -groebnerMatrix(34,196)/(groebnerMatrix(34,157)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial46( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(46,82) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(46,83) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(46,85) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(46,86) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(46,88) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(46,95) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(46,115) = groebnerMatrix(27,181)/(groebnerMatrix(27,168)); groebnerMatrix(46,118) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(46,119) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(46,120) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(46,121) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(46,122) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(46,123) = -groebnerMatrix(39,183)/(groebnerMatrix(39,162)); groebnerMatrix(46,124) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(46,131) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(46,139) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(46,158) = groebnerMatrix(27,188)/(groebnerMatrix(27,168)); groebnerMatrix(46,163) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(46,164) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(46,165) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(46,166) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(46,167) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(46,168) = -groebnerMatrix(39,192)/(groebnerMatrix(39,162)); groebnerMatrix(46,169) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(46,176) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(46,184) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(46,193) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial47( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(47,56) = -groebnerMatrix(38,162)/(groebnerMatrix(38,161)); groebnerMatrix(47,79) = groebnerMatrix(21,173)/(groebnerMatrix(21,167)); groebnerMatrix(47,82) = -groebnerMatrix(38,170)/(groebnerMatrix(38,161)); groebnerMatrix(47,83) = -groebnerMatrix(38,171)/(groebnerMatrix(38,161)); groebnerMatrix(47,85) = -groebnerMatrix(38,173)/(groebnerMatrix(38,161)); groebnerMatrix(47,86) = -groebnerMatrix(38,174)/(groebnerMatrix(38,161)); groebnerMatrix(47,88) = -groebnerMatrix(38,176)/(groebnerMatrix(38,161)); groebnerMatrix(47,95) = -groebnerMatrix(38,177)/(groebnerMatrix(38,161)); groebnerMatrix(47,118) = -groebnerMatrix(38,178)/(groebnerMatrix(38,161)); groebnerMatrix(47,119) = -groebnerMatrix(38,179)/(groebnerMatrix(38,161)); groebnerMatrix(47,120) = -groebnerMatrix(38,180)/(groebnerMatrix(38,161)); groebnerMatrix(47,121) = -groebnerMatrix(38,181)/(groebnerMatrix(38,161)); groebnerMatrix(47,122) = -groebnerMatrix(38,182)/(groebnerMatrix(38,161)); groebnerMatrix(47,123) = -groebnerMatrix(38,183)/(groebnerMatrix(38,161)); groebnerMatrix(47,124) = -groebnerMatrix(38,184)/(groebnerMatrix(38,161)); groebnerMatrix(47,131) = -groebnerMatrix(38,185)/(groebnerMatrix(38,161)); groebnerMatrix(47,139) = -groebnerMatrix(38,186)/(groebnerMatrix(38,161)); groebnerMatrix(47,159) = groebnerMatrix(21,189)/(groebnerMatrix(21,167)); groebnerMatrix(47,163) = -groebnerMatrix(38,187)/(groebnerMatrix(38,161)); groebnerMatrix(47,164) = -groebnerMatrix(38,188)/(groebnerMatrix(38,161)); groebnerMatrix(47,165) = -groebnerMatrix(38,189)/(groebnerMatrix(38,161)); groebnerMatrix(47,166) = -groebnerMatrix(38,190)/(groebnerMatrix(38,161)); groebnerMatrix(47,167) = -groebnerMatrix(38,191)/(groebnerMatrix(38,161)); groebnerMatrix(47,168) = -groebnerMatrix(38,192)/(groebnerMatrix(38,161)); groebnerMatrix(47,169) = -groebnerMatrix(38,193)/(groebnerMatrix(38,161)); groebnerMatrix(47,176) = -groebnerMatrix(38,194)/(groebnerMatrix(38,161)); groebnerMatrix(47,184) = -groebnerMatrix(38,195)/(groebnerMatrix(38,161)); groebnerMatrix(47,193) = -groebnerMatrix(38,196)/(groebnerMatrix(38,161)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial48( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(48,55) = -groebnerMatrix(37,161)/(groebnerMatrix(37,160)); groebnerMatrix(48,56) = -groebnerMatrix(37,162)/(groebnerMatrix(37,160)); groebnerMatrix(48,80) = groebnerMatrix(11,174)/(groebnerMatrix(11,166)); groebnerMatrix(48,82) = -groebnerMatrix(37,170)/(groebnerMatrix(37,160)); groebnerMatrix(48,83) = -groebnerMatrix(37,171)/(groebnerMatrix(37,160)); groebnerMatrix(48,85) = -groebnerMatrix(37,173)/(groebnerMatrix(37,160)); groebnerMatrix(48,86) = -groebnerMatrix(37,174)/(groebnerMatrix(37,160)); groebnerMatrix(48,88) = -groebnerMatrix(37,176)/(groebnerMatrix(37,160)); groebnerMatrix(48,95) = -groebnerMatrix(37,177)/(groebnerMatrix(37,160)); groebnerMatrix(48,117) = groebnerMatrix(11,183)/(groebnerMatrix(11,166)); groebnerMatrix(48,118) = -groebnerMatrix(37,178)/(groebnerMatrix(37,160)); groebnerMatrix(48,119) = -groebnerMatrix(37,179)/(groebnerMatrix(37,160)); groebnerMatrix(48,120) = -groebnerMatrix(37,180)/(groebnerMatrix(37,160)); groebnerMatrix(48,121) = -groebnerMatrix(37,181)/(groebnerMatrix(37,160)); groebnerMatrix(48,122) = -groebnerMatrix(37,182)/(groebnerMatrix(37,160)); groebnerMatrix(48,123) = -groebnerMatrix(37,183)/(groebnerMatrix(37,160)); groebnerMatrix(48,124) = -groebnerMatrix(37,184)/(groebnerMatrix(37,160)); groebnerMatrix(48,131) = -groebnerMatrix(37,185)/(groebnerMatrix(37,160)); groebnerMatrix(48,139) = -groebnerMatrix(37,186)/(groebnerMatrix(37,160)); groebnerMatrix(48,163) = -groebnerMatrix(37,187)/(groebnerMatrix(37,160)); groebnerMatrix(48,164) = -groebnerMatrix(37,188)/(groebnerMatrix(37,160)); groebnerMatrix(48,165) = -groebnerMatrix(37,189)/(groebnerMatrix(37,160)); groebnerMatrix(48,166) = -groebnerMatrix(37,190)/(groebnerMatrix(37,160)); groebnerMatrix(48,167) = -groebnerMatrix(37,191)/(groebnerMatrix(37,160)); groebnerMatrix(48,168) = -groebnerMatrix(37,192)/(groebnerMatrix(37,160)); groebnerMatrix(48,169) = -groebnerMatrix(37,193)/(groebnerMatrix(37,160)); groebnerMatrix(48,176) = -groebnerMatrix(37,194)/(groebnerMatrix(37,160)); groebnerMatrix(48,184) = -groebnerMatrix(37,195)/(groebnerMatrix(37,160)); groebnerMatrix(48,193) = -groebnerMatrix(37,196)/(groebnerMatrix(37,160)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial49( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(49,54) = -groebnerMatrix(36,160)/(groebnerMatrix(36,159)); groebnerMatrix(49,55) = -groebnerMatrix(36,161)/(groebnerMatrix(36,159)); groebnerMatrix(49,56) = -groebnerMatrix(36,162)/(groebnerMatrix(36,159)); groebnerMatrix(49,82) = -groebnerMatrix(36,170)/(groebnerMatrix(36,159)); groebnerMatrix(49,83) = -groebnerMatrix(36,171)/(groebnerMatrix(36,159)); groebnerMatrix(49,85) = -groebnerMatrix(36,173)/(groebnerMatrix(36,159)); groebnerMatrix(49,86) = -groebnerMatrix(36,174)/(groebnerMatrix(36,159)); groebnerMatrix(49,88) = -groebnerMatrix(36,176)/(groebnerMatrix(36,159)); groebnerMatrix(49,95) = -groebnerMatrix(36,177)/(groebnerMatrix(36,159)); groebnerMatrix(49,105) = groebnerMatrix(27,181)/(groebnerMatrix(27,168)); groebnerMatrix(49,118) = -groebnerMatrix(36,178)/(groebnerMatrix(36,159)); groebnerMatrix(49,119) = -groebnerMatrix(36,179)/(groebnerMatrix(36,159)); groebnerMatrix(49,120) = -groebnerMatrix(36,180)/(groebnerMatrix(36,159)); groebnerMatrix(49,121) = -groebnerMatrix(36,181)/(groebnerMatrix(36,159)); groebnerMatrix(49,122) = -groebnerMatrix(36,182)/(groebnerMatrix(36,159)); groebnerMatrix(49,123) = -groebnerMatrix(36,183)/(groebnerMatrix(36,159)); groebnerMatrix(49,124) = -groebnerMatrix(36,184)/(groebnerMatrix(36,159)); groebnerMatrix(49,131) = -groebnerMatrix(36,185)/(groebnerMatrix(36,159)); groebnerMatrix(49,139) = -groebnerMatrix(36,186)/(groebnerMatrix(36,159)); groebnerMatrix(49,146) = groebnerMatrix(27,188)/(groebnerMatrix(27,168)); groebnerMatrix(49,163) = -groebnerMatrix(36,187)/(groebnerMatrix(36,159)); groebnerMatrix(49,164) = -groebnerMatrix(36,188)/(groebnerMatrix(36,159)); groebnerMatrix(49,165) = -groebnerMatrix(36,189)/(groebnerMatrix(36,159)); groebnerMatrix(49,166) = -groebnerMatrix(36,190)/(groebnerMatrix(36,159)); groebnerMatrix(49,167) = -groebnerMatrix(36,191)/(groebnerMatrix(36,159)); groebnerMatrix(49,168) = -groebnerMatrix(36,192)/(groebnerMatrix(36,159)); groebnerMatrix(49,169) = -groebnerMatrix(36,193)/(groebnerMatrix(36,159)); groebnerMatrix(49,176) = -groebnerMatrix(36,194)/(groebnerMatrix(36,159)); groebnerMatrix(49,184) = -groebnerMatrix(36,195)/(groebnerMatrix(36,159)); groebnerMatrix(49,193) = -groebnerMatrix(36,196)/(groebnerMatrix(36,159)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial50( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(50,53) = -groebnerMatrix(35,159)/(groebnerMatrix(35,158)); groebnerMatrix(50,54) = -groebnerMatrix(35,160)/(groebnerMatrix(35,158)); groebnerMatrix(50,55) = -groebnerMatrix(35,161)/(groebnerMatrix(35,158)); groebnerMatrix(50,56) = -groebnerMatrix(35,162)/(groebnerMatrix(35,158)); groebnerMatrix(50,76) = groebnerMatrix(20,170)/(groebnerMatrix(20,164)); groebnerMatrix(50,82) = -groebnerMatrix(35,170)/(groebnerMatrix(35,158)); groebnerMatrix(50,83) = -groebnerMatrix(35,171)/(groebnerMatrix(35,158)); groebnerMatrix(50,85) = -groebnerMatrix(35,173)/(groebnerMatrix(35,158)); groebnerMatrix(50,86) = -groebnerMatrix(35,174)/(groebnerMatrix(35,158)); groebnerMatrix(50,88) = -groebnerMatrix(35,176)/(groebnerMatrix(35,158)); groebnerMatrix(50,95) = -groebnerMatrix(35,177)/(groebnerMatrix(35,158)); groebnerMatrix(50,118) = -groebnerMatrix(35,178)/(groebnerMatrix(35,158)); groebnerMatrix(50,119) = -groebnerMatrix(35,179)/(groebnerMatrix(35,158)); groebnerMatrix(50,120) = -groebnerMatrix(35,180)/(groebnerMatrix(35,158)); groebnerMatrix(50,121) = -groebnerMatrix(35,181)/(groebnerMatrix(35,158)); groebnerMatrix(50,122) = -groebnerMatrix(35,182)/(groebnerMatrix(35,158)); groebnerMatrix(50,123) = -groebnerMatrix(35,183)/(groebnerMatrix(35,158)); groebnerMatrix(50,124) = -groebnerMatrix(35,184)/(groebnerMatrix(35,158)); groebnerMatrix(50,131) = -groebnerMatrix(35,185)/(groebnerMatrix(35,158)); groebnerMatrix(50,139) = -groebnerMatrix(35,186)/(groebnerMatrix(35,158)); groebnerMatrix(50,162) = groebnerMatrix(20,192)/(groebnerMatrix(20,164)); groebnerMatrix(50,163) = -groebnerMatrix(35,187)/(groebnerMatrix(35,158)); groebnerMatrix(50,164) = -groebnerMatrix(35,188)/(groebnerMatrix(35,158)); groebnerMatrix(50,165) = -groebnerMatrix(35,189)/(groebnerMatrix(35,158)); groebnerMatrix(50,166) = -groebnerMatrix(35,190)/(groebnerMatrix(35,158)); groebnerMatrix(50,167) = -groebnerMatrix(35,191)/(groebnerMatrix(35,158)); groebnerMatrix(50,168) = -groebnerMatrix(35,192)/(groebnerMatrix(35,158)); groebnerMatrix(50,169) = -groebnerMatrix(35,193)/(groebnerMatrix(35,158)); groebnerMatrix(50,176) = -groebnerMatrix(35,194)/(groebnerMatrix(35,158)); groebnerMatrix(50,184) = -groebnerMatrix(35,195)/(groebnerMatrix(35,158)); groebnerMatrix(50,193) = -groebnerMatrix(35,196)/(groebnerMatrix(35,158)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial51( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(51,52) = -groebnerMatrix(34,158)/(groebnerMatrix(34,157)); groebnerMatrix(51,53) = -groebnerMatrix(34,159)/(groebnerMatrix(34,157)); groebnerMatrix(51,54) = -groebnerMatrix(34,160)/(groebnerMatrix(34,157)); groebnerMatrix(51,55) = -groebnerMatrix(34,161)/(groebnerMatrix(34,157)); groebnerMatrix(51,56) = -groebnerMatrix(34,162)/(groebnerMatrix(34,157)); groebnerMatrix(51,77) = groebnerMatrix(12,171)/(groebnerMatrix(12,163)); groebnerMatrix(51,82) = -groebnerMatrix(34,170)/(groebnerMatrix(34,157)); groebnerMatrix(51,83) = -groebnerMatrix(34,171)/(groebnerMatrix(34,157)); groebnerMatrix(51,85) = -groebnerMatrix(34,173)/(groebnerMatrix(34,157)); groebnerMatrix(51,86) = -groebnerMatrix(34,174)/(groebnerMatrix(34,157)); groebnerMatrix(51,88) = -groebnerMatrix(34,176)/(groebnerMatrix(34,157)); groebnerMatrix(51,95) = -groebnerMatrix(34,177)/(groebnerMatrix(34,157)); groebnerMatrix(51,114) = groebnerMatrix(12,180)/(groebnerMatrix(12,163)); groebnerMatrix(51,118) = -groebnerMatrix(34,178)/(groebnerMatrix(34,157)); groebnerMatrix(51,119) = -groebnerMatrix(34,179)/(groebnerMatrix(34,157)); groebnerMatrix(51,120) = -groebnerMatrix(34,180)/(groebnerMatrix(34,157)); groebnerMatrix(51,121) = -groebnerMatrix(34,181)/(groebnerMatrix(34,157)); groebnerMatrix(51,122) = -groebnerMatrix(34,182)/(groebnerMatrix(34,157)); groebnerMatrix(51,123) = -groebnerMatrix(34,183)/(groebnerMatrix(34,157)); groebnerMatrix(51,124) = -groebnerMatrix(34,184)/(groebnerMatrix(34,157)); groebnerMatrix(51,131) = -groebnerMatrix(34,185)/(groebnerMatrix(34,157)); groebnerMatrix(51,139) = -groebnerMatrix(34,186)/(groebnerMatrix(34,157)); groebnerMatrix(51,163) = -groebnerMatrix(34,187)/(groebnerMatrix(34,157)); groebnerMatrix(51,164) = -groebnerMatrix(34,188)/(groebnerMatrix(34,157)); groebnerMatrix(51,165) = -groebnerMatrix(34,189)/(groebnerMatrix(34,157)); groebnerMatrix(51,166) = -groebnerMatrix(34,190)/(groebnerMatrix(34,157)); groebnerMatrix(51,167) = -groebnerMatrix(34,191)/(groebnerMatrix(34,157)); groebnerMatrix(51,168) = -groebnerMatrix(34,192)/(groebnerMatrix(34,157)); groebnerMatrix(51,169) = -groebnerMatrix(34,193)/(groebnerMatrix(34,157)); groebnerMatrix(51,176) = -groebnerMatrix(34,194)/(groebnerMatrix(34,157)); groebnerMatrix(51,184) = -groebnerMatrix(34,195)/(groebnerMatrix(34,157)); groebnerMatrix(51,193) = -groebnerMatrix(34,196)/(groebnerMatrix(34,157)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial52( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(52,51) = -groebnerMatrix(33,157)/(groebnerMatrix(33,156)); groebnerMatrix(52,52) = -groebnerMatrix(33,158)/(groebnerMatrix(33,156)); groebnerMatrix(52,53) = -groebnerMatrix(33,159)/(groebnerMatrix(33,156)); groebnerMatrix(52,54) = -groebnerMatrix(33,160)/(groebnerMatrix(33,156)); groebnerMatrix(52,55) = -groebnerMatrix(33,161)/(groebnerMatrix(33,156)); groebnerMatrix(52,56) = -groebnerMatrix(33,162)/(groebnerMatrix(33,156)); groebnerMatrix(52,74) = groebnerMatrix(21,173)/(groebnerMatrix(21,167)); groebnerMatrix(52,82) = -groebnerMatrix(33,170)/(groebnerMatrix(33,156)); groebnerMatrix(52,83) = -groebnerMatrix(33,171)/(groebnerMatrix(33,156)); groebnerMatrix(52,85) = -groebnerMatrix(33,173)/(groebnerMatrix(33,156)); groebnerMatrix(52,86) = -groebnerMatrix(33,174)/(groebnerMatrix(33,156)); groebnerMatrix(52,88) = -groebnerMatrix(33,176)/(groebnerMatrix(33,156)); groebnerMatrix(52,95) = -groebnerMatrix(33,177)/(groebnerMatrix(33,156)); groebnerMatrix(52,118) = -groebnerMatrix(33,178)/(groebnerMatrix(33,156)); groebnerMatrix(52,119) = -groebnerMatrix(33,179)/(groebnerMatrix(33,156)); groebnerMatrix(52,120) = -groebnerMatrix(33,180)/(groebnerMatrix(33,156)); groebnerMatrix(52,121) = -groebnerMatrix(33,181)/(groebnerMatrix(33,156)); groebnerMatrix(52,122) = -groebnerMatrix(33,182)/(groebnerMatrix(33,156)); groebnerMatrix(52,123) = -groebnerMatrix(33,183)/(groebnerMatrix(33,156)); groebnerMatrix(52,124) = -groebnerMatrix(33,184)/(groebnerMatrix(33,156)); groebnerMatrix(52,131) = -groebnerMatrix(33,185)/(groebnerMatrix(33,156)); groebnerMatrix(52,139) = -groebnerMatrix(33,186)/(groebnerMatrix(33,156)); groebnerMatrix(52,154) = groebnerMatrix(21,189)/(groebnerMatrix(21,167)); groebnerMatrix(52,163) = -groebnerMatrix(33,187)/(groebnerMatrix(33,156)); groebnerMatrix(52,164) = -groebnerMatrix(33,188)/(groebnerMatrix(33,156)); groebnerMatrix(52,165) = -groebnerMatrix(33,189)/(groebnerMatrix(33,156)); groebnerMatrix(52,166) = -groebnerMatrix(33,190)/(groebnerMatrix(33,156)); groebnerMatrix(52,167) = -groebnerMatrix(33,191)/(groebnerMatrix(33,156)); groebnerMatrix(52,168) = -groebnerMatrix(33,192)/(groebnerMatrix(33,156)); groebnerMatrix(52,169) = -groebnerMatrix(33,193)/(groebnerMatrix(33,156)); groebnerMatrix(52,176) = -groebnerMatrix(33,194)/(groebnerMatrix(33,156)); groebnerMatrix(52,184) = -groebnerMatrix(33,195)/(groebnerMatrix(33,156)); groebnerMatrix(52,193) = -groebnerMatrix(33,196)/(groebnerMatrix(33,156)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial53( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(53,50) = -groebnerMatrix(32,156)/(groebnerMatrix(32,155)); groebnerMatrix(53,51) = -groebnerMatrix(32,157)/(groebnerMatrix(32,155)); groebnerMatrix(53,52) = -groebnerMatrix(32,158)/(groebnerMatrix(32,155)); groebnerMatrix(53,53) = -groebnerMatrix(32,159)/(groebnerMatrix(32,155)); groebnerMatrix(53,54) = -groebnerMatrix(32,160)/(groebnerMatrix(32,155)); groebnerMatrix(53,55) = -groebnerMatrix(32,161)/(groebnerMatrix(32,155)); groebnerMatrix(53,56) = -groebnerMatrix(32,162)/(groebnerMatrix(32,155)); groebnerMatrix(53,75) = groebnerMatrix(11,174)/(groebnerMatrix(11,166)); groebnerMatrix(53,82) = -groebnerMatrix(32,170)/(groebnerMatrix(32,155)); groebnerMatrix(53,83) = -groebnerMatrix(32,171)/(groebnerMatrix(32,155)); groebnerMatrix(53,85) = -groebnerMatrix(32,173)/(groebnerMatrix(32,155)); groebnerMatrix(53,86) = -groebnerMatrix(32,174)/(groebnerMatrix(32,155)); groebnerMatrix(53,88) = -groebnerMatrix(32,176)/(groebnerMatrix(32,155)); groebnerMatrix(53,95) = -groebnerMatrix(32,177)/(groebnerMatrix(32,155)); groebnerMatrix(53,116) = groebnerMatrix(11,183)/(groebnerMatrix(11,166)); groebnerMatrix(53,118) = -groebnerMatrix(32,178)/(groebnerMatrix(32,155)); groebnerMatrix(53,119) = -groebnerMatrix(32,179)/(groebnerMatrix(32,155)); groebnerMatrix(53,120) = -groebnerMatrix(32,180)/(groebnerMatrix(32,155)); groebnerMatrix(53,121) = -groebnerMatrix(32,181)/(groebnerMatrix(32,155)); groebnerMatrix(53,122) = -groebnerMatrix(32,182)/(groebnerMatrix(32,155)); groebnerMatrix(53,123) = -groebnerMatrix(32,183)/(groebnerMatrix(32,155)); groebnerMatrix(53,124) = -groebnerMatrix(32,184)/(groebnerMatrix(32,155)); groebnerMatrix(53,131) = -groebnerMatrix(32,185)/(groebnerMatrix(32,155)); groebnerMatrix(53,139) = -groebnerMatrix(32,186)/(groebnerMatrix(32,155)); groebnerMatrix(53,163) = -groebnerMatrix(32,187)/(groebnerMatrix(32,155)); groebnerMatrix(53,164) = -groebnerMatrix(32,188)/(groebnerMatrix(32,155)); groebnerMatrix(53,165) = -groebnerMatrix(32,189)/(groebnerMatrix(32,155)); groebnerMatrix(53,166) = -groebnerMatrix(32,190)/(groebnerMatrix(32,155)); groebnerMatrix(53,167) = -groebnerMatrix(32,191)/(groebnerMatrix(32,155)); groebnerMatrix(53,168) = -groebnerMatrix(32,192)/(groebnerMatrix(32,155)); groebnerMatrix(53,169) = -groebnerMatrix(32,193)/(groebnerMatrix(32,155)); groebnerMatrix(53,176) = -groebnerMatrix(32,194)/(groebnerMatrix(32,155)); groebnerMatrix(53,184) = -groebnerMatrix(32,195)/(groebnerMatrix(32,155)); groebnerMatrix(53,193) = -groebnerMatrix(32,196)/(groebnerMatrix(32,155)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial54( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(54,49) = -groebnerMatrix(31,155)/(groebnerMatrix(31,153)); groebnerMatrix(54,50) = -groebnerMatrix(31,156)/(groebnerMatrix(31,153)); groebnerMatrix(54,51) = -groebnerMatrix(31,157)/(groebnerMatrix(31,153)); groebnerMatrix(54,52) = -groebnerMatrix(31,158)/(groebnerMatrix(31,153)); groebnerMatrix(54,53) = -groebnerMatrix(31,159)/(groebnerMatrix(31,153)); groebnerMatrix(54,54) = -groebnerMatrix(31,160)/(groebnerMatrix(31,153)); groebnerMatrix(54,55) = -groebnerMatrix(31,161)/(groebnerMatrix(31,153)); groebnerMatrix(54,56) = -groebnerMatrix(31,162)/(groebnerMatrix(31,153)); groebnerMatrix(54,71) = groebnerMatrix(20,170)/(groebnerMatrix(20,164)); groebnerMatrix(54,82) = -groebnerMatrix(31,170)/(groebnerMatrix(31,153)); groebnerMatrix(54,83) = -groebnerMatrix(31,171)/(groebnerMatrix(31,153)); groebnerMatrix(54,85) = -groebnerMatrix(31,173)/(groebnerMatrix(31,153)); groebnerMatrix(54,86) = -groebnerMatrix(31,174)/(groebnerMatrix(31,153)); groebnerMatrix(54,88) = -groebnerMatrix(31,176)/(groebnerMatrix(31,153)); groebnerMatrix(54,95) = -groebnerMatrix(31,177)/(groebnerMatrix(31,153)); groebnerMatrix(54,118) = -groebnerMatrix(31,178)/(groebnerMatrix(31,153)); groebnerMatrix(54,119) = -groebnerMatrix(31,179)/(groebnerMatrix(31,153)); groebnerMatrix(54,120) = -groebnerMatrix(31,180)/(groebnerMatrix(31,153)); groebnerMatrix(54,121) = -groebnerMatrix(31,181)/(groebnerMatrix(31,153)); groebnerMatrix(54,122) = -groebnerMatrix(31,182)/(groebnerMatrix(31,153)); groebnerMatrix(54,123) = -groebnerMatrix(31,183)/(groebnerMatrix(31,153)); groebnerMatrix(54,124) = -groebnerMatrix(31,184)/(groebnerMatrix(31,153)); groebnerMatrix(54,131) = -groebnerMatrix(31,185)/(groebnerMatrix(31,153)); groebnerMatrix(54,139) = -groebnerMatrix(31,186)/(groebnerMatrix(31,153)); groebnerMatrix(54,161) = groebnerMatrix(20,192)/(groebnerMatrix(20,164)); groebnerMatrix(54,163) = -groebnerMatrix(31,187)/(groebnerMatrix(31,153)); groebnerMatrix(54,164) = -groebnerMatrix(31,188)/(groebnerMatrix(31,153)); groebnerMatrix(54,165) = -groebnerMatrix(31,189)/(groebnerMatrix(31,153)); groebnerMatrix(54,166) = -groebnerMatrix(31,190)/(groebnerMatrix(31,153)); groebnerMatrix(54,167) = -groebnerMatrix(31,191)/(groebnerMatrix(31,153)); groebnerMatrix(54,168) = -groebnerMatrix(31,192)/(groebnerMatrix(31,153)); groebnerMatrix(54,169) = -groebnerMatrix(31,193)/(groebnerMatrix(31,153)); groebnerMatrix(54,176) = -groebnerMatrix(31,194)/(groebnerMatrix(31,153)); groebnerMatrix(54,184) = -groebnerMatrix(31,195)/(groebnerMatrix(31,153)); groebnerMatrix(54,193) = -groebnerMatrix(31,196)/(groebnerMatrix(31,153)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial55( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(55,38) = groebnerMatrix(38,162)/(groebnerMatrix(38,161)); groebnerMatrix(55,71) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(55,72) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(55,74) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(55,75) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(55,76) = groebnerMatrix(38,170)/(groebnerMatrix(38,161)); groebnerMatrix(55,77) = groebnerMatrix(38,171)/(groebnerMatrix(38,161)); groebnerMatrix(55,79) = groebnerMatrix(38,173)/(groebnerMatrix(38,161)); groebnerMatrix(55,80) = groebnerMatrix(38,174)/(groebnerMatrix(38,161)); groebnerMatrix(55,86) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(55,87) = groebnerMatrix(38,176)/(groebnerMatrix(38,161)); groebnerMatrix(55,93) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(55,94) = groebnerMatrix(38,177)/(groebnerMatrix(38,161)); groebnerMatrix(55,107) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(55,108) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(55,109) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(55,110) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(55,111) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(55,112) = groebnerMatrix(38,178)/(groebnerMatrix(38,161)); groebnerMatrix(55,113) = groebnerMatrix(38,179)/(groebnerMatrix(38,161)); groebnerMatrix(55,114) = groebnerMatrix(38,180)/(groebnerMatrix(38,161)); groebnerMatrix(55,115) = groebnerMatrix(38,181)/(groebnerMatrix(38,161)); groebnerMatrix(55,116) = (groebnerMatrix(38,182)/(groebnerMatrix(38,161))-groebnerMatrix(39,183)/(groebnerMatrix(39,162))); groebnerMatrix(55,117) = groebnerMatrix(38,183)/(groebnerMatrix(38,161)); groebnerMatrix(55,122) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(55,123) = groebnerMatrix(38,184)/(groebnerMatrix(38,161)); groebnerMatrix(55,129) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(55,130) = groebnerMatrix(38,185)/(groebnerMatrix(38,161)); groebnerMatrix(55,137) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(55,138) = groebnerMatrix(38,186)/(groebnerMatrix(38,161)); groebnerMatrix(55,152) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(55,153) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(55,154) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(55,155) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(55,156) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(55,157) = groebnerMatrix(38,187)/(groebnerMatrix(38,161)); groebnerMatrix(55,158) = groebnerMatrix(38,188)/(groebnerMatrix(38,161)); groebnerMatrix(55,159) = groebnerMatrix(38,189)/(groebnerMatrix(38,161)); groebnerMatrix(55,160) = groebnerMatrix(38,190)/(groebnerMatrix(38,161)); groebnerMatrix(55,161) = (groebnerMatrix(38,191)/(groebnerMatrix(38,161))-groebnerMatrix(39,192)/(groebnerMatrix(39,162))); groebnerMatrix(55,162) = groebnerMatrix(38,192)/(groebnerMatrix(38,161)); groebnerMatrix(55,167) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(55,168) = groebnerMatrix(38,193)/(groebnerMatrix(38,161)); groebnerMatrix(55,174) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(55,175) = groebnerMatrix(38,194)/(groebnerMatrix(38,161)); groebnerMatrix(55,182) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(55,183) = groebnerMatrix(38,195)/(groebnerMatrix(38,161)); groebnerMatrix(55,191) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); groebnerMatrix(55,192) = groebnerMatrix(38,196)/(groebnerMatrix(38,161)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial56( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(56,37) = groebnerMatrix(37,161)/(groebnerMatrix(37,160)); groebnerMatrix(56,38) = groebnerMatrix(37,162)/(groebnerMatrix(37,160)); groebnerMatrix(56,67) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(56,68) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(56,70) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(56,74) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(56,76) = groebnerMatrix(37,170)/(groebnerMatrix(37,160)); groebnerMatrix(56,77) = groebnerMatrix(37,171)/(groebnerMatrix(37,160)); groebnerMatrix(56,79) = groebnerMatrix(37,173)/(groebnerMatrix(37,160)); groebnerMatrix(56,80) = groebnerMatrix(37,174)/(groebnerMatrix(37,160)); groebnerMatrix(56,85) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(56,87) = groebnerMatrix(37,176)/(groebnerMatrix(37,160)); groebnerMatrix(56,92) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(56,94) = groebnerMatrix(37,177)/(groebnerMatrix(37,160)); groebnerMatrix(56,103) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(56,104) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(56,105) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(56,106) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(56,110) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(56,112) = groebnerMatrix(37,178)/(groebnerMatrix(37,160)); groebnerMatrix(56,113) = groebnerMatrix(37,179)/(groebnerMatrix(37,160)); groebnerMatrix(56,114) = groebnerMatrix(37,180)/(groebnerMatrix(37,160)); groebnerMatrix(56,115) = (groebnerMatrix(37,181)/(groebnerMatrix(37,160))-groebnerMatrix(39,183)/(groebnerMatrix(39,162))); groebnerMatrix(56,116) = groebnerMatrix(37,182)/(groebnerMatrix(37,160)); groebnerMatrix(56,117) = groebnerMatrix(37,183)/(groebnerMatrix(37,160)); groebnerMatrix(56,121) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(56,123) = groebnerMatrix(37,184)/(groebnerMatrix(37,160)); groebnerMatrix(56,128) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(56,130) = groebnerMatrix(37,185)/(groebnerMatrix(37,160)); groebnerMatrix(56,136) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(56,138) = groebnerMatrix(37,186)/(groebnerMatrix(37,160)); groebnerMatrix(56,148) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(56,149) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(56,150) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(56,151) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(56,155) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(56,157) = groebnerMatrix(37,187)/(groebnerMatrix(37,160)); groebnerMatrix(56,158) = groebnerMatrix(37,188)/(groebnerMatrix(37,160)); groebnerMatrix(56,159) = groebnerMatrix(37,189)/(groebnerMatrix(37,160)); groebnerMatrix(56,160) = (groebnerMatrix(37,190)/(groebnerMatrix(37,160))-groebnerMatrix(39,192)/(groebnerMatrix(39,162))); groebnerMatrix(56,161) = groebnerMatrix(37,191)/(groebnerMatrix(37,160)); groebnerMatrix(56,162) = groebnerMatrix(37,192)/(groebnerMatrix(37,160)); groebnerMatrix(56,166) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(56,168) = groebnerMatrix(37,193)/(groebnerMatrix(37,160)); groebnerMatrix(56,173) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(56,175) = groebnerMatrix(37,194)/(groebnerMatrix(37,160)); groebnerMatrix(56,181) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(56,183) = groebnerMatrix(37,195)/(groebnerMatrix(37,160)); groebnerMatrix(56,190) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); groebnerMatrix(56,192) = groebnerMatrix(37,196)/(groebnerMatrix(37,160)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial57( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(57,36) = groebnerMatrix(36,160)/(groebnerMatrix(36,159)); groebnerMatrix(57,37) = groebnerMatrix(36,161)/(groebnerMatrix(36,159)); groebnerMatrix(57,38) = groebnerMatrix(36,162)/(groebnerMatrix(36,159)); groebnerMatrix(57,64) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(57,65) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(57,69) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(57,73) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(57,76) = groebnerMatrix(36,170)/(groebnerMatrix(36,159)); groebnerMatrix(57,77) = groebnerMatrix(36,171)/(groebnerMatrix(36,159)); groebnerMatrix(57,79) = groebnerMatrix(36,173)/(groebnerMatrix(36,159)); groebnerMatrix(57,80) = groebnerMatrix(36,174)/(groebnerMatrix(36,159)); groebnerMatrix(57,84) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(57,87) = groebnerMatrix(36,176)/(groebnerMatrix(36,159)); groebnerMatrix(57,91) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(57,94) = groebnerMatrix(36,177)/(groebnerMatrix(36,159)); groebnerMatrix(57,100) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(57,101) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(57,102) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(57,105) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(57,109) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(57,112) = groebnerMatrix(36,178)/(groebnerMatrix(36,159)); groebnerMatrix(57,113) = groebnerMatrix(36,179)/(groebnerMatrix(36,159)); groebnerMatrix(57,114) = (groebnerMatrix(36,180)/(groebnerMatrix(36,159))-groebnerMatrix(39,183)/(groebnerMatrix(39,162))); groebnerMatrix(57,115) = groebnerMatrix(36,181)/(groebnerMatrix(36,159)); groebnerMatrix(57,116) = groebnerMatrix(36,182)/(groebnerMatrix(36,159)); groebnerMatrix(57,117) = groebnerMatrix(36,183)/(groebnerMatrix(36,159)); groebnerMatrix(57,120) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(57,123) = groebnerMatrix(36,184)/(groebnerMatrix(36,159)); groebnerMatrix(57,127) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(57,130) = groebnerMatrix(36,185)/(groebnerMatrix(36,159)); groebnerMatrix(57,135) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(57,138) = groebnerMatrix(36,186)/(groebnerMatrix(36,159)); groebnerMatrix(57,145) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(57,146) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(57,147) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(57,150) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(57,154) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(57,157) = groebnerMatrix(36,187)/(groebnerMatrix(36,159)); groebnerMatrix(57,158) = groebnerMatrix(36,188)/(groebnerMatrix(36,159)); groebnerMatrix(57,159) = (groebnerMatrix(36,189)/(groebnerMatrix(36,159))-groebnerMatrix(39,192)/(groebnerMatrix(39,162))); groebnerMatrix(57,160) = groebnerMatrix(36,190)/(groebnerMatrix(36,159)); groebnerMatrix(57,161) = groebnerMatrix(36,191)/(groebnerMatrix(36,159)); groebnerMatrix(57,162) = groebnerMatrix(36,192)/(groebnerMatrix(36,159)); groebnerMatrix(57,165) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(57,168) = groebnerMatrix(36,193)/(groebnerMatrix(36,159)); groebnerMatrix(57,172) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(57,175) = groebnerMatrix(36,194)/(groebnerMatrix(36,159)); groebnerMatrix(57,180) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(57,183) = groebnerMatrix(36,195)/(groebnerMatrix(36,159)); groebnerMatrix(57,189) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); groebnerMatrix(57,192) = groebnerMatrix(36,196)/(groebnerMatrix(36,159)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial58( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(58,35) = groebnerMatrix(35,159)/(groebnerMatrix(35,158)); groebnerMatrix(58,36) = groebnerMatrix(35,160)/(groebnerMatrix(35,158)); groebnerMatrix(58,37) = groebnerMatrix(35,161)/(groebnerMatrix(35,158)); groebnerMatrix(58,38) = groebnerMatrix(35,162)/(groebnerMatrix(35,158)); groebnerMatrix(58,62) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(58,63) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(58,68) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(58,72) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(58,76) = groebnerMatrix(35,170)/(groebnerMatrix(35,158)); groebnerMatrix(58,77) = groebnerMatrix(35,171)/(groebnerMatrix(35,158)); groebnerMatrix(58,79) = groebnerMatrix(35,173)/(groebnerMatrix(35,158)); groebnerMatrix(58,80) = groebnerMatrix(35,174)/(groebnerMatrix(35,158)); groebnerMatrix(58,83) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(58,87) = groebnerMatrix(35,176)/(groebnerMatrix(35,158)); groebnerMatrix(58,90) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(58,94) = groebnerMatrix(35,177)/(groebnerMatrix(35,158)); groebnerMatrix(58,98) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(58,99) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(58,101) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(58,104) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(58,108) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(58,112) = groebnerMatrix(35,178)/(groebnerMatrix(35,158)); groebnerMatrix(58,113) = (groebnerMatrix(35,179)/(groebnerMatrix(35,158))-groebnerMatrix(39,183)/(groebnerMatrix(39,162))); groebnerMatrix(58,114) = groebnerMatrix(35,180)/(groebnerMatrix(35,158)); groebnerMatrix(58,115) = groebnerMatrix(35,181)/(groebnerMatrix(35,158)); groebnerMatrix(58,116) = groebnerMatrix(35,182)/(groebnerMatrix(35,158)); groebnerMatrix(58,117) = groebnerMatrix(35,183)/(groebnerMatrix(35,158)); groebnerMatrix(58,119) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(58,123) = groebnerMatrix(35,184)/(groebnerMatrix(35,158)); groebnerMatrix(58,126) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(58,130) = groebnerMatrix(35,185)/(groebnerMatrix(35,158)); groebnerMatrix(58,134) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(58,138) = groebnerMatrix(35,186)/(groebnerMatrix(35,158)); groebnerMatrix(58,143) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(58,144) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(58,146) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(58,149) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(58,153) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(58,157) = groebnerMatrix(35,187)/(groebnerMatrix(35,158)); groebnerMatrix(58,158) = (groebnerMatrix(35,188)/(groebnerMatrix(35,158))-groebnerMatrix(39,192)/(groebnerMatrix(39,162))); groebnerMatrix(58,159) = groebnerMatrix(35,189)/(groebnerMatrix(35,158)); groebnerMatrix(58,160) = groebnerMatrix(35,190)/(groebnerMatrix(35,158)); groebnerMatrix(58,161) = groebnerMatrix(35,191)/(groebnerMatrix(35,158)); groebnerMatrix(58,162) = groebnerMatrix(35,192)/(groebnerMatrix(35,158)); groebnerMatrix(58,164) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(58,168) = groebnerMatrix(35,193)/(groebnerMatrix(35,158)); groebnerMatrix(58,171) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(58,175) = groebnerMatrix(35,194)/(groebnerMatrix(35,158)); groebnerMatrix(58,179) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(58,183) = groebnerMatrix(35,195)/(groebnerMatrix(35,158)); groebnerMatrix(58,188) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); groebnerMatrix(58,192) = groebnerMatrix(35,196)/(groebnerMatrix(35,158)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial59( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(59,34) = groebnerMatrix(34,158)/(groebnerMatrix(34,157)); groebnerMatrix(59,35) = groebnerMatrix(34,159)/(groebnerMatrix(34,157)); groebnerMatrix(59,36) = groebnerMatrix(34,160)/(groebnerMatrix(34,157)); groebnerMatrix(59,37) = groebnerMatrix(34,161)/(groebnerMatrix(34,157)); groebnerMatrix(59,38) = groebnerMatrix(34,162)/(groebnerMatrix(34,157)); groebnerMatrix(59,61) = -groebnerMatrix(39,170)/(groebnerMatrix(39,162)); groebnerMatrix(59,62) = -groebnerMatrix(39,171)/(groebnerMatrix(39,162)); groebnerMatrix(59,67) = -groebnerMatrix(39,173)/(groebnerMatrix(39,162)); groebnerMatrix(59,71) = -groebnerMatrix(39,174)/(groebnerMatrix(39,162)); groebnerMatrix(59,76) = groebnerMatrix(34,170)/(groebnerMatrix(34,157)); groebnerMatrix(59,77) = groebnerMatrix(34,171)/(groebnerMatrix(34,157)); groebnerMatrix(59,79) = groebnerMatrix(34,173)/(groebnerMatrix(34,157)); groebnerMatrix(59,80) = groebnerMatrix(34,174)/(groebnerMatrix(34,157)); groebnerMatrix(59,82) = -groebnerMatrix(39,176)/(groebnerMatrix(39,162)); groebnerMatrix(59,87) = groebnerMatrix(34,176)/(groebnerMatrix(34,157)); groebnerMatrix(59,89) = -groebnerMatrix(39,177)/(groebnerMatrix(39,162)); groebnerMatrix(59,94) = groebnerMatrix(34,177)/(groebnerMatrix(34,157)); groebnerMatrix(59,97) = -groebnerMatrix(39,178)/(groebnerMatrix(39,162)); groebnerMatrix(59,98) = -groebnerMatrix(39,179)/(groebnerMatrix(39,162)); groebnerMatrix(59,100) = -groebnerMatrix(39,180)/(groebnerMatrix(39,162)); groebnerMatrix(59,103) = -groebnerMatrix(39,181)/(groebnerMatrix(39,162)); groebnerMatrix(59,107) = -groebnerMatrix(39,182)/(groebnerMatrix(39,162)); groebnerMatrix(59,112) = (groebnerMatrix(34,178)/(groebnerMatrix(34,157))-groebnerMatrix(39,183)/(groebnerMatrix(39,162))); groebnerMatrix(59,113) = groebnerMatrix(34,179)/(groebnerMatrix(34,157)); groebnerMatrix(59,114) = groebnerMatrix(34,180)/(groebnerMatrix(34,157)); groebnerMatrix(59,115) = groebnerMatrix(34,181)/(groebnerMatrix(34,157)); groebnerMatrix(59,116) = groebnerMatrix(34,182)/(groebnerMatrix(34,157)); groebnerMatrix(59,117) = groebnerMatrix(34,183)/(groebnerMatrix(34,157)); groebnerMatrix(59,118) = -groebnerMatrix(39,184)/(groebnerMatrix(39,162)); groebnerMatrix(59,123) = groebnerMatrix(34,184)/(groebnerMatrix(34,157)); groebnerMatrix(59,125) = -groebnerMatrix(39,185)/(groebnerMatrix(39,162)); groebnerMatrix(59,130) = groebnerMatrix(34,185)/(groebnerMatrix(34,157)); groebnerMatrix(59,133) = -groebnerMatrix(39,186)/(groebnerMatrix(39,162)); groebnerMatrix(59,138) = groebnerMatrix(34,186)/(groebnerMatrix(34,157)); groebnerMatrix(59,142) = -groebnerMatrix(39,187)/(groebnerMatrix(39,162)); groebnerMatrix(59,143) = -groebnerMatrix(39,188)/(groebnerMatrix(39,162)); groebnerMatrix(59,145) = -groebnerMatrix(39,189)/(groebnerMatrix(39,162)); groebnerMatrix(59,148) = -groebnerMatrix(39,190)/(groebnerMatrix(39,162)); groebnerMatrix(59,152) = -groebnerMatrix(39,191)/(groebnerMatrix(39,162)); groebnerMatrix(59,157) = (groebnerMatrix(34,187)/(groebnerMatrix(34,157))-groebnerMatrix(39,192)/(groebnerMatrix(39,162))); groebnerMatrix(59,158) = groebnerMatrix(34,188)/(groebnerMatrix(34,157)); groebnerMatrix(59,159) = groebnerMatrix(34,189)/(groebnerMatrix(34,157)); groebnerMatrix(59,160) = groebnerMatrix(34,190)/(groebnerMatrix(34,157)); groebnerMatrix(59,161) = groebnerMatrix(34,191)/(groebnerMatrix(34,157)); groebnerMatrix(59,162) = groebnerMatrix(34,192)/(groebnerMatrix(34,157)); groebnerMatrix(59,163) = -groebnerMatrix(39,193)/(groebnerMatrix(39,162)); groebnerMatrix(59,168) = groebnerMatrix(34,193)/(groebnerMatrix(34,157)); groebnerMatrix(59,170) = -groebnerMatrix(39,194)/(groebnerMatrix(39,162)); groebnerMatrix(59,175) = groebnerMatrix(34,194)/(groebnerMatrix(34,157)); groebnerMatrix(59,178) = -groebnerMatrix(39,195)/(groebnerMatrix(39,162)); groebnerMatrix(59,183) = groebnerMatrix(34,195)/(groebnerMatrix(34,157)); groebnerMatrix(59,187) = -groebnerMatrix(39,196)/(groebnerMatrix(39,162)); groebnerMatrix(59,192) = groebnerMatrix(34,196)/(groebnerMatrix(34,157)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial60( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(60,33) = groebnerMatrix(33,157)/(groebnerMatrix(33,156)); groebnerMatrix(60,34) = groebnerMatrix(33,158)/(groebnerMatrix(33,156)); groebnerMatrix(60,35) = groebnerMatrix(33,159)/(groebnerMatrix(33,156)); groebnerMatrix(60,36) = groebnerMatrix(33,160)/(groebnerMatrix(33,156)); groebnerMatrix(60,37) = (groebnerMatrix(33,161)/(groebnerMatrix(33,156))-groebnerMatrix(38,162)/(groebnerMatrix(38,161))); groebnerMatrix(60,38) = groebnerMatrix(33,162)/(groebnerMatrix(33,156)); groebnerMatrix(60,71) = -groebnerMatrix(38,170)/(groebnerMatrix(38,161)); groebnerMatrix(60,72) = -groebnerMatrix(38,171)/(groebnerMatrix(38,161)); groebnerMatrix(60,74) = -groebnerMatrix(38,173)/(groebnerMatrix(38,161)); groebnerMatrix(60,75) = -groebnerMatrix(38,174)/(groebnerMatrix(38,161)); groebnerMatrix(60,76) = groebnerMatrix(33,170)/(groebnerMatrix(33,156)); groebnerMatrix(60,77) = groebnerMatrix(33,171)/(groebnerMatrix(33,156)); groebnerMatrix(60,79) = groebnerMatrix(33,173)/(groebnerMatrix(33,156)); groebnerMatrix(60,80) = groebnerMatrix(33,174)/(groebnerMatrix(33,156)); groebnerMatrix(60,86) = -groebnerMatrix(38,176)/(groebnerMatrix(38,161)); groebnerMatrix(60,87) = groebnerMatrix(33,176)/(groebnerMatrix(33,156)); groebnerMatrix(60,93) = -groebnerMatrix(38,177)/(groebnerMatrix(38,161)); groebnerMatrix(60,94) = groebnerMatrix(33,177)/(groebnerMatrix(33,156)); groebnerMatrix(60,107) = -groebnerMatrix(38,178)/(groebnerMatrix(38,161)); groebnerMatrix(60,108) = -groebnerMatrix(38,179)/(groebnerMatrix(38,161)); groebnerMatrix(60,109) = -groebnerMatrix(38,180)/(groebnerMatrix(38,161)); groebnerMatrix(60,110) = -groebnerMatrix(38,181)/(groebnerMatrix(38,161)); groebnerMatrix(60,111) = -groebnerMatrix(38,182)/(groebnerMatrix(38,161)); groebnerMatrix(60,112) = groebnerMatrix(33,178)/(groebnerMatrix(33,156)); groebnerMatrix(60,113) = groebnerMatrix(33,179)/(groebnerMatrix(33,156)); groebnerMatrix(60,114) = groebnerMatrix(33,180)/(groebnerMatrix(33,156)); groebnerMatrix(60,115) = groebnerMatrix(33,181)/(groebnerMatrix(33,156)); groebnerMatrix(60,116) = (groebnerMatrix(33,182)/(groebnerMatrix(33,156))-groebnerMatrix(38,183)/(groebnerMatrix(38,161))); groebnerMatrix(60,117) = groebnerMatrix(33,183)/(groebnerMatrix(33,156)); groebnerMatrix(60,122) = -groebnerMatrix(38,184)/(groebnerMatrix(38,161)); groebnerMatrix(60,123) = groebnerMatrix(33,184)/(groebnerMatrix(33,156)); groebnerMatrix(60,129) = -groebnerMatrix(38,185)/(groebnerMatrix(38,161)); groebnerMatrix(60,130) = groebnerMatrix(33,185)/(groebnerMatrix(33,156)); groebnerMatrix(60,137) = -groebnerMatrix(38,186)/(groebnerMatrix(38,161)); groebnerMatrix(60,138) = groebnerMatrix(33,186)/(groebnerMatrix(33,156)); groebnerMatrix(60,152) = -groebnerMatrix(38,187)/(groebnerMatrix(38,161)); groebnerMatrix(60,153) = -groebnerMatrix(38,188)/(groebnerMatrix(38,161)); groebnerMatrix(60,154) = -groebnerMatrix(38,189)/(groebnerMatrix(38,161)); groebnerMatrix(60,155) = -groebnerMatrix(38,190)/(groebnerMatrix(38,161)); groebnerMatrix(60,156) = -groebnerMatrix(38,191)/(groebnerMatrix(38,161)); groebnerMatrix(60,157) = groebnerMatrix(33,187)/(groebnerMatrix(33,156)); groebnerMatrix(60,158) = groebnerMatrix(33,188)/(groebnerMatrix(33,156)); groebnerMatrix(60,159) = groebnerMatrix(33,189)/(groebnerMatrix(33,156)); groebnerMatrix(60,160) = groebnerMatrix(33,190)/(groebnerMatrix(33,156)); groebnerMatrix(60,161) = (groebnerMatrix(33,191)/(groebnerMatrix(33,156))-groebnerMatrix(38,192)/(groebnerMatrix(38,161))); groebnerMatrix(60,162) = groebnerMatrix(33,192)/(groebnerMatrix(33,156)); groebnerMatrix(60,167) = -groebnerMatrix(38,193)/(groebnerMatrix(38,161)); groebnerMatrix(60,168) = groebnerMatrix(33,193)/(groebnerMatrix(33,156)); groebnerMatrix(60,174) = -groebnerMatrix(38,194)/(groebnerMatrix(38,161)); groebnerMatrix(60,175) = groebnerMatrix(33,194)/(groebnerMatrix(33,156)); groebnerMatrix(60,182) = -groebnerMatrix(38,195)/(groebnerMatrix(38,161)); groebnerMatrix(60,183) = groebnerMatrix(33,195)/(groebnerMatrix(33,156)); groebnerMatrix(60,191) = -groebnerMatrix(38,196)/(groebnerMatrix(38,161)); groebnerMatrix(60,192) = groebnerMatrix(33,196)/(groebnerMatrix(33,156)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial61( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(61,32) = (groebnerMatrix(32,156)/(groebnerMatrix(32,155))-groebnerMatrix(37,161)/(groebnerMatrix(37,160))); groebnerMatrix(61,33) = groebnerMatrix(32,157)/(groebnerMatrix(32,155)); groebnerMatrix(61,34) = groebnerMatrix(32,158)/(groebnerMatrix(32,155)); groebnerMatrix(61,35) = groebnerMatrix(32,159)/(groebnerMatrix(32,155)); groebnerMatrix(61,36) = groebnerMatrix(32,160)/(groebnerMatrix(32,155)); groebnerMatrix(61,37) = (groebnerMatrix(32,161)/(groebnerMatrix(32,155))-groebnerMatrix(37,162)/(groebnerMatrix(37,160))); groebnerMatrix(61,38) = groebnerMatrix(32,162)/(groebnerMatrix(32,155)); groebnerMatrix(61,71) = -groebnerMatrix(37,170)/(groebnerMatrix(37,160)); groebnerMatrix(61,72) = -groebnerMatrix(37,171)/(groebnerMatrix(37,160)); groebnerMatrix(61,74) = -groebnerMatrix(37,173)/(groebnerMatrix(37,160)); groebnerMatrix(61,75) = -groebnerMatrix(37,174)/(groebnerMatrix(37,160)); groebnerMatrix(61,76) = groebnerMatrix(32,170)/(groebnerMatrix(32,155)); groebnerMatrix(61,77) = groebnerMatrix(32,171)/(groebnerMatrix(32,155)); groebnerMatrix(61,79) = groebnerMatrix(32,173)/(groebnerMatrix(32,155)); groebnerMatrix(61,80) = groebnerMatrix(32,174)/(groebnerMatrix(32,155)); groebnerMatrix(61,86) = -groebnerMatrix(37,176)/(groebnerMatrix(37,160)); groebnerMatrix(61,87) = groebnerMatrix(32,176)/(groebnerMatrix(32,155)); groebnerMatrix(61,93) = -groebnerMatrix(37,177)/(groebnerMatrix(37,160)); groebnerMatrix(61,94) = groebnerMatrix(32,177)/(groebnerMatrix(32,155)); groebnerMatrix(61,107) = -groebnerMatrix(37,178)/(groebnerMatrix(37,160)); groebnerMatrix(61,108) = -groebnerMatrix(37,179)/(groebnerMatrix(37,160)); groebnerMatrix(61,109) = -groebnerMatrix(37,180)/(groebnerMatrix(37,160)); groebnerMatrix(61,110) = -groebnerMatrix(37,181)/(groebnerMatrix(37,160)); groebnerMatrix(61,111) = -groebnerMatrix(37,182)/(groebnerMatrix(37,160)); groebnerMatrix(61,112) = groebnerMatrix(32,178)/(groebnerMatrix(32,155)); groebnerMatrix(61,113) = groebnerMatrix(32,179)/(groebnerMatrix(32,155)); groebnerMatrix(61,114) = groebnerMatrix(32,180)/(groebnerMatrix(32,155)); groebnerMatrix(61,115) = groebnerMatrix(32,181)/(groebnerMatrix(32,155)); groebnerMatrix(61,116) = (groebnerMatrix(32,182)/(groebnerMatrix(32,155))-groebnerMatrix(37,183)/(groebnerMatrix(37,160))); groebnerMatrix(61,117) = groebnerMatrix(32,183)/(groebnerMatrix(32,155)); groebnerMatrix(61,122) = -groebnerMatrix(37,184)/(groebnerMatrix(37,160)); groebnerMatrix(61,123) = groebnerMatrix(32,184)/(groebnerMatrix(32,155)); groebnerMatrix(61,129) = -groebnerMatrix(37,185)/(groebnerMatrix(37,160)); groebnerMatrix(61,130) = groebnerMatrix(32,185)/(groebnerMatrix(32,155)); groebnerMatrix(61,137) = -groebnerMatrix(37,186)/(groebnerMatrix(37,160)); groebnerMatrix(61,138) = groebnerMatrix(32,186)/(groebnerMatrix(32,155)); groebnerMatrix(61,152) = -groebnerMatrix(37,187)/(groebnerMatrix(37,160)); groebnerMatrix(61,153) = -groebnerMatrix(37,188)/(groebnerMatrix(37,160)); groebnerMatrix(61,154) = -groebnerMatrix(37,189)/(groebnerMatrix(37,160)); groebnerMatrix(61,155) = -groebnerMatrix(37,190)/(groebnerMatrix(37,160)); groebnerMatrix(61,156) = -groebnerMatrix(37,191)/(groebnerMatrix(37,160)); groebnerMatrix(61,157) = groebnerMatrix(32,187)/(groebnerMatrix(32,155)); groebnerMatrix(61,158) = groebnerMatrix(32,188)/(groebnerMatrix(32,155)); groebnerMatrix(61,159) = groebnerMatrix(32,189)/(groebnerMatrix(32,155)); groebnerMatrix(61,160) = groebnerMatrix(32,190)/(groebnerMatrix(32,155)); groebnerMatrix(61,161) = (groebnerMatrix(32,191)/(groebnerMatrix(32,155))-groebnerMatrix(37,192)/(groebnerMatrix(37,160))); groebnerMatrix(61,162) = groebnerMatrix(32,192)/(groebnerMatrix(32,155)); groebnerMatrix(61,167) = -groebnerMatrix(37,193)/(groebnerMatrix(37,160)); groebnerMatrix(61,168) = groebnerMatrix(32,193)/(groebnerMatrix(32,155)); groebnerMatrix(61,174) = -groebnerMatrix(37,194)/(groebnerMatrix(37,160)); groebnerMatrix(61,175) = groebnerMatrix(32,194)/(groebnerMatrix(32,155)); groebnerMatrix(61,182) = -groebnerMatrix(37,195)/(groebnerMatrix(37,160)); groebnerMatrix(61,183) = groebnerMatrix(32,195)/(groebnerMatrix(32,155)); groebnerMatrix(61,191) = -groebnerMatrix(37,196)/(groebnerMatrix(37,160)); groebnerMatrix(61,192) = groebnerMatrix(32,196)/(groebnerMatrix(32,155)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial62( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(62,32) = groebnerMatrix(32,156)/(groebnerMatrix(32,155)); groebnerMatrix(62,33) = groebnerMatrix(32,157)/(groebnerMatrix(32,155)); groebnerMatrix(62,34) = groebnerMatrix(32,158)/(groebnerMatrix(32,155)); groebnerMatrix(62,35) = groebnerMatrix(32,159)/(groebnerMatrix(32,155)); groebnerMatrix(62,36) = (groebnerMatrix(32,160)/(groebnerMatrix(32,155))-groebnerMatrix(38,162)/(groebnerMatrix(38,161))); groebnerMatrix(62,37) = groebnerMatrix(32,161)/(groebnerMatrix(32,155)); groebnerMatrix(62,38) = groebnerMatrix(32,162)/(groebnerMatrix(32,155)); groebnerMatrix(62,67) = -groebnerMatrix(38,170)/(groebnerMatrix(38,161)); groebnerMatrix(62,68) = -groebnerMatrix(38,171)/(groebnerMatrix(38,161)); groebnerMatrix(62,70) = -groebnerMatrix(38,173)/(groebnerMatrix(38,161)); groebnerMatrix(62,74) = -groebnerMatrix(38,174)/(groebnerMatrix(38,161)); groebnerMatrix(62,76) = groebnerMatrix(32,170)/(groebnerMatrix(32,155)); groebnerMatrix(62,77) = groebnerMatrix(32,171)/(groebnerMatrix(32,155)); groebnerMatrix(62,79) = groebnerMatrix(32,173)/(groebnerMatrix(32,155)); groebnerMatrix(62,80) = groebnerMatrix(32,174)/(groebnerMatrix(32,155)); groebnerMatrix(62,85) = -groebnerMatrix(38,176)/(groebnerMatrix(38,161)); groebnerMatrix(62,87) = groebnerMatrix(32,176)/(groebnerMatrix(32,155)); groebnerMatrix(62,92) = -groebnerMatrix(38,177)/(groebnerMatrix(38,161)); groebnerMatrix(62,94) = groebnerMatrix(32,177)/(groebnerMatrix(32,155)); groebnerMatrix(62,103) = -groebnerMatrix(38,178)/(groebnerMatrix(38,161)); groebnerMatrix(62,104) = -groebnerMatrix(38,179)/(groebnerMatrix(38,161)); groebnerMatrix(62,105) = -groebnerMatrix(38,180)/(groebnerMatrix(38,161)); groebnerMatrix(62,106) = -groebnerMatrix(38,181)/(groebnerMatrix(38,161)); groebnerMatrix(62,110) = -groebnerMatrix(38,182)/(groebnerMatrix(38,161)); groebnerMatrix(62,112) = groebnerMatrix(32,178)/(groebnerMatrix(32,155)); groebnerMatrix(62,113) = groebnerMatrix(32,179)/(groebnerMatrix(32,155)); groebnerMatrix(62,114) = groebnerMatrix(32,180)/(groebnerMatrix(32,155)); groebnerMatrix(62,115) = (groebnerMatrix(32,181)/(groebnerMatrix(32,155))-groebnerMatrix(38,183)/(groebnerMatrix(38,161))); groebnerMatrix(62,116) = groebnerMatrix(32,182)/(groebnerMatrix(32,155)); groebnerMatrix(62,117) = groebnerMatrix(32,183)/(groebnerMatrix(32,155)); groebnerMatrix(62,121) = -groebnerMatrix(38,184)/(groebnerMatrix(38,161)); groebnerMatrix(62,123) = groebnerMatrix(32,184)/(groebnerMatrix(32,155)); groebnerMatrix(62,128) = -groebnerMatrix(38,185)/(groebnerMatrix(38,161)); groebnerMatrix(62,130) = groebnerMatrix(32,185)/(groebnerMatrix(32,155)); groebnerMatrix(62,136) = -groebnerMatrix(38,186)/(groebnerMatrix(38,161)); groebnerMatrix(62,138) = groebnerMatrix(32,186)/(groebnerMatrix(32,155)); groebnerMatrix(62,148) = -groebnerMatrix(38,187)/(groebnerMatrix(38,161)); groebnerMatrix(62,149) = -groebnerMatrix(38,188)/(groebnerMatrix(38,161)); groebnerMatrix(62,150) = -groebnerMatrix(38,189)/(groebnerMatrix(38,161)); groebnerMatrix(62,151) = -groebnerMatrix(38,190)/(groebnerMatrix(38,161)); groebnerMatrix(62,155) = -groebnerMatrix(38,191)/(groebnerMatrix(38,161)); groebnerMatrix(62,157) = groebnerMatrix(32,187)/(groebnerMatrix(32,155)); groebnerMatrix(62,158) = groebnerMatrix(32,188)/(groebnerMatrix(32,155)); groebnerMatrix(62,159) = groebnerMatrix(32,189)/(groebnerMatrix(32,155)); groebnerMatrix(62,160) = (groebnerMatrix(32,190)/(groebnerMatrix(32,155))-groebnerMatrix(38,192)/(groebnerMatrix(38,161))); groebnerMatrix(62,161) = groebnerMatrix(32,191)/(groebnerMatrix(32,155)); groebnerMatrix(62,162) = groebnerMatrix(32,192)/(groebnerMatrix(32,155)); groebnerMatrix(62,166) = -groebnerMatrix(38,193)/(groebnerMatrix(38,161)); groebnerMatrix(62,168) = groebnerMatrix(32,193)/(groebnerMatrix(32,155)); groebnerMatrix(62,173) = -groebnerMatrix(38,194)/(groebnerMatrix(38,161)); groebnerMatrix(62,175) = groebnerMatrix(32,194)/(groebnerMatrix(32,155)); groebnerMatrix(62,181) = -groebnerMatrix(38,195)/(groebnerMatrix(38,161)); groebnerMatrix(62,183) = groebnerMatrix(32,195)/(groebnerMatrix(32,155)); groebnerMatrix(62,190) = -groebnerMatrix(38,196)/(groebnerMatrix(38,161)); groebnerMatrix(62,192) = groebnerMatrix(32,196)/(groebnerMatrix(32,155)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial63( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(63,31) = -groebnerMatrix(36,160)/(groebnerMatrix(36,159)); groebnerMatrix(63,32) = -groebnerMatrix(36,161)/(groebnerMatrix(36,159)); groebnerMatrix(63,34) = groebnerMatrix(16,158)/(groebnerMatrix(16,154)); groebnerMatrix(63,37) = -groebnerMatrix(36,162)/(groebnerMatrix(36,159)); groebnerMatrix(63,71) = -groebnerMatrix(36,170)/(groebnerMatrix(36,159)); groebnerMatrix(63,72) = -groebnerMatrix(36,171)/(groebnerMatrix(36,159)); groebnerMatrix(63,74) = -groebnerMatrix(36,173)/(groebnerMatrix(36,159)); groebnerMatrix(63,75) = -groebnerMatrix(36,174)/(groebnerMatrix(36,159)); groebnerMatrix(63,86) = -groebnerMatrix(36,176)/(groebnerMatrix(36,159)); groebnerMatrix(63,93) = -groebnerMatrix(36,177)/(groebnerMatrix(36,159)); groebnerMatrix(63,107) = -groebnerMatrix(36,178)/(groebnerMatrix(36,159)); groebnerMatrix(63,108) = -groebnerMatrix(36,179)/(groebnerMatrix(36,159)); groebnerMatrix(63,109) = -groebnerMatrix(36,180)/(groebnerMatrix(36,159)); groebnerMatrix(63,110) = -groebnerMatrix(36,181)/(groebnerMatrix(36,159)); groebnerMatrix(63,111) = -groebnerMatrix(36,182)/(groebnerMatrix(36,159)); groebnerMatrix(63,116) = -groebnerMatrix(36,183)/(groebnerMatrix(36,159)); groebnerMatrix(63,122) = -groebnerMatrix(36,184)/(groebnerMatrix(36,159)); groebnerMatrix(63,129) = -groebnerMatrix(36,185)/(groebnerMatrix(36,159)); groebnerMatrix(63,137) = -groebnerMatrix(36,186)/(groebnerMatrix(36,159)); groebnerMatrix(63,152) = -groebnerMatrix(36,187)/(groebnerMatrix(36,159)); groebnerMatrix(63,153) = -groebnerMatrix(36,188)/(groebnerMatrix(36,159)); groebnerMatrix(63,154) = -groebnerMatrix(36,189)/(groebnerMatrix(36,159)); groebnerMatrix(63,155) = -groebnerMatrix(36,190)/(groebnerMatrix(36,159)); groebnerMatrix(63,156) = -groebnerMatrix(36,191)/(groebnerMatrix(36,159)); groebnerMatrix(63,161) = -groebnerMatrix(36,192)/(groebnerMatrix(36,159)); groebnerMatrix(63,167) = -groebnerMatrix(36,193)/(groebnerMatrix(36,159)); groebnerMatrix(63,168) = groebnerMatrix(16,193)/(groebnerMatrix(16,154)); groebnerMatrix(63,174) = -groebnerMatrix(36,194)/(groebnerMatrix(36,159)); groebnerMatrix(63,182) = -groebnerMatrix(36,195)/(groebnerMatrix(36,159)); groebnerMatrix(63,191) = -groebnerMatrix(36,196)/(groebnerMatrix(36,159)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial64( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(64,34) = groebnerMatrix(16,158)/(groebnerMatrix(16,154)); groebnerMatrix(64,35) = -groebnerMatrix(38,162)/(groebnerMatrix(38,161)); groebnerMatrix(64,64) = -groebnerMatrix(38,170)/(groebnerMatrix(38,161)); groebnerMatrix(64,65) = -groebnerMatrix(38,171)/(groebnerMatrix(38,161)); groebnerMatrix(64,69) = -groebnerMatrix(38,173)/(groebnerMatrix(38,161)); groebnerMatrix(64,73) = -groebnerMatrix(38,174)/(groebnerMatrix(38,161)); groebnerMatrix(64,84) = -groebnerMatrix(38,176)/(groebnerMatrix(38,161)); groebnerMatrix(64,91) = -groebnerMatrix(38,177)/(groebnerMatrix(38,161)); groebnerMatrix(64,100) = -groebnerMatrix(38,178)/(groebnerMatrix(38,161)); groebnerMatrix(64,101) = -groebnerMatrix(38,179)/(groebnerMatrix(38,161)); groebnerMatrix(64,102) = -groebnerMatrix(38,180)/(groebnerMatrix(38,161)); groebnerMatrix(64,105) = -groebnerMatrix(38,181)/(groebnerMatrix(38,161)); groebnerMatrix(64,109) = -groebnerMatrix(38,182)/(groebnerMatrix(38,161)); groebnerMatrix(64,114) = -groebnerMatrix(38,183)/(groebnerMatrix(38,161)); groebnerMatrix(64,120) = -groebnerMatrix(38,184)/(groebnerMatrix(38,161)); groebnerMatrix(64,127) = -groebnerMatrix(38,185)/(groebnerMatrix(38,161)); groebnerMatrix(64,135) = -groebnerMatrix(38,186)/(groebnerMatrix(38,161)); groebnerMatrix(64,145) = -groebnerMatrix(38,187)/(groebnerMatrix(38,161)); groebnerMatrix(64,146) = -groebnerMatrix(38,188)/(groebnerMatrix(38,161)); groebnerMatrix(64,147) = -groebnerMatrix(38,189)/(groebnerMatrix(38,161)); groebnerMatrix(64,150) = -groebnerMatrix(38,190)/(groebnerMatrix(38,161)); groebnerMatrix(64,154) = -groebnerMatrix(38,191)/(groebnerMatrix(38,161)); groebnerMatrix(64,159) = -groebnerMatrix(38,192)/(groebnerMatrix(38,161)); groebnerMatrix(64,165) = -groebnerMatrix(38,193)/(groebnerMatrix(38,161)); groebnerMatrix(64,168) = groebnerMatrix(16,193)/(groebnerMatrix(16,154)); groebnerMatrix(64,172) = -groebnerMatrix(38,194)/(groebnerMatrix(38,161)); groebnerMatrix(64,180) = -groebnerMatrix(38,195)/(groebnerMatrix(38,161)); groebnerMatrix(64,189) = -groebnerMatrix(38,196)/(groebnerMatrix(38,161)); } void opengv::relative_pose::modules::fivept_kneip::sPolynomial65( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(65,30) = -groebnerMatrix(35,159)/(groebnerMatrix(35,158)); groebnerMatrix(65,31) = (groebnerMatrix(31,155)/(groebnerMatrix(31,153))-groebnerMatrix(35,160)/(groebnerMatrix(35,158))); groebnerMatrix(65,32) = (groebnerMatrix(31,156)/(groebnerMatrix(31,153))-groebnerMatrix(35,161)/(groebnerMatrix(35,158))); groebnerMatrix(65,33) = groebnerMatrix(31,157)/(groebnerMatrix(31,153)); groebnerMatrix(65,34) = groebnerMatrix(31,158)/(groebnerMatrix(31,153)); groebnerMatrix(65,35) = groebnerMatrix(31,159)/(groebnerMatrix(31,153)); groebnerMatrix(65,36) = groebnerMatrix(31,160)/(groebnerMatrix(31,153)); groebnerMatrix(65,37) = (groebnerMatrix(31,161)/(groebnerMatrix(31,153))-groebnerMatrix(35,162)/(groebnerMatrix(35,158))); groebnerMatrix(65,38) = groebnerMatrix(31,162)/(groebnerMatrix(31,153)); groebnerMatrix(65,71) = -groebnerMatrix(35,170)/(groebnerMatrix(35,158)); groebnerMatrix(65,72) = -groebnerMatrix(35,171)/(groebnerMatrix(35,158)); groebnerMatrix(65,74) = -groebnerMatrix(35,173)/(groebnerMatrix(35,158)); groebnerMatrix(65,75) = -groebnerMatrix(35,174)/(groebnerMatrix(35,158)); groebnerMatrix(65,76) = groebnerMatrix(31,170)/(groebnerMatrix(31,153)); groebnerMatrix(65,77) = groebnerMatrix(31,171)/(groebnerMatrix(31,153)); groebnerMatrix(65,79) = groebnerMatrix(31,173)/(groebnerMatrix(31,153)); groebnerMatrix(65,80) = groebnerMatrix(31,174)/(groebnerMatrix(31,153)); groebnerMatrix(65,86) = -groebnerMatrix(35,176)/(groebnerMatrix(35,158)); groebnerMatrix(65,87) = groebnerMatrix(31,176)/(groebnerMatrix(31,153)); groebnerMatrix(65,93) = -groebnerMatrix(35,177)/(groebnerMatrix(35,158)); groebnerMatrix(65,94) = groebnerMatrix(31,177)/(groebnerMatrix(31,153)); groebnerMatrix(65,107) = -groebnerMatrix(35,178)/(groebnerMatrix(35,158)); groebnerMatrix(65,108) = -groebnerMatrix(35,179)/(groebnerMatrix(35,158)); groebnerMatrix(65,109) = -groebnerMatrix(35,180)/(groebnerMatrix(35,158)); groebnerMatrix(65,110) = -groebnerMatrix(35,181)/(groebnerMatrix(35,158)); groebnerMatrix(65,111) = -groebnerMatrix(35,182)/(groebnerMatrix(35,158)); groebnerMatrix(65,112) = groebnerMatrix(31,178)/(groebnerMatrix(31,153)); groebnerMatrix(65,113) = groebnerMatrix(31,179)/(groebnerMatrix(31,153)); groebnerMatrix(65,114) = groebnerMatrix(31,180)/(groebnerMatrix(31,153)); groebnerMatrix(65,115) = groebnerMatrix(31,181)/(groebnerMatrix(31,153)); groebnerMatrix(65,116) = (groebnerMatrix(31,182)/(groebnerMatrix(31,153))-groebnerMatrix(35,183)/(groebnerMatrix(35,158))); groebnerMatrix(65,117) = groebnerMatrix(31,183)/(groebnerMatrix(31,153)); groebnerMatrix(65,122) = -groebnerMatrix(35,184)/(groebnerMatrix(35,158)); groebnerMatrix(65,123) = groebnerMatrix(31,184)/(groebnerMatrix(31,153)); groebnerMatrix(65,129) = -groebnerMatrix(35,185)/(groebnerMatrix(35,158)); groebnerMatrix(65,130) = groebnerMatrix(31,185)/(groebnerMatrix(31,153)); groebnerMatrix(65,137) = -groebnerMatrix(35,186)/(groebnerMatrix(35,158)); groebnerMatrix(65,138) = groebnerMatrix(31,186)/(groebnerMatrix(31,153)); groebnerMatrix(65,152) = -groebnerMatrix(35,187)/(groebnerMatrix(35,158)); groebnerMatrix(65,153) = -groebnerMatrix(35,188)/(groebnerMatrix(35,158)); groebnerMatrix(65,154) = -groebnerMatrix(35,189)/(groebnerMatrix(35,158)); groebnerMatrix(65,155) = -groebnerMatrix(35,190)/(groebnerMatrix(35,158)); groebnerMatrix(65,156) = -groebnerMatrix(35,191)/(groebnerMatrix(35,158)); groebnerMatrix(65,157) = groebnerMatrix(31,187)/(groebnerMatrix(31,153)); groebnerMatrix(65,158) = groebnerMatrix(31,188)/(groebnerMatrix(31,153)); groebnerMatrix(65,159) = groebnerMatrix(31,189)/(groebnerMatrix(31,153)); groebnerMatrix(65,160) = groebnerMatrix(31,190)/(groebnerMatrix(31,153)); groebnerMatrix(65,161) = (groebnerMatrix(31,191)/(groebnerMatrix(31,153))-groebnerMatrix(35,192)/(groebnerMatrix(35,158))); groebnerMatrix(65,162) = groebnerMatrix(31,192)/(groebnerMatrix(31,153)); groebnerMatrix(65,167) = -groebnerMatrix(35,193)/(groebnerMatrix(35,158)); groebnerMatrix(65,168) = groebnerMatrix(31,193)/(groebnerMatrix(31,153)); groebnerMatrix(65,174) = -groebnerMatrix(35,194)/(groebnerMatrix(35,158)); groebnerMatrix(65,175) = groebnerMatrix(31,194)/(groebnerMatrix(31,153)); groebnerMatrix(65,182) = -groebnerMatrix(35,195)/(groebnerMatrix(35,158)); groebnerMatrix(65,183) = groebnerMatrix(31,195)/(groebnerMatrix(31,153)); groebnerMatrix(65,191) = -groebnerMatrix(35,196)/(groebnerMatrix(35,158)); groebnerMatrix(65,192) = groebnerMatrix(31,196)/(groebnerMatrix(31,153)); } opengv/src/relative_pose/modules/fivept_kneip/init.cpp0000664016516101651610000010362013344612246022243 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include Eigen::Matrix opengv::relative_pose::modules::fivept_kneip::initEpncpRowR( std::vector > & c123_1, std::vector > & c123_2 ) { Eigen::Matrix row = Eigen::Matrix::Zero(); row(0,0) = -c123_1[1](0,0)*c123_2[2](1,2)+c123_1[1](0,0)*c123_2[2](2,1)+c123_1[0](0,1)*c123_2[2](1,2)-c123_1[0](0,1)*c123_2[1](2,2)-c123_1[0](1,0)*c123_2[2](2,1)+c123_1[0](1,0)*c123_2[1](2,2); row(0,1) = -c123_1[1](0,0)*c123_2[1](1,2)+c123_1[1](0,0)*c123_2[1](2,1)+c123_1[0](0,1)*c123_2[2](1,1)-c123_1[0](0,1)*c123_2[1](2,1)-c123_1[0](1,0)*c123_2[2](1,1)+c123_1[0](1,0)*c123_2[1](1,2); row(0,2) = -c123_1[1](0,0)*c123_2[2](0,2)+c123_1[1](0,0)*c123_2[2](2,0)+c123_1[0](0,1)*c123_2[2](0,2)-c123_1[0](0,1)*c123_2[0](2,2)-c123_1[0](1,0)*c123_2[2](2,0)+c123_1[0](1,0)*c123_2[0](2,2); row(0,3) = -c123_1[1](0,0)*c123_2[1](0,2)-c123_1[1](0,0)*c123_2[0](1,2)+c123_1[1](0,0)*c123_2[1](2,0)+c123_1[1](0,0)*c123_2[0](2,1)+c123_1[0](0,1)*c123_2[2](0,1)+c123_1[0](0,1)*c123_2[2](1,0)-c123_1[0](0,1)*c123_2[1](2,0)-c123_1[0](0,1)*c123_2[0](2,1)-c123_1[0](1,0)*c123_2[2](0,1)+c123_1[0](1,0)*c123_2[1](0,2)-c123_1[0](1,0)*c123_2[2](1,0)+c123_1[0](1,0)*c123_2[0](1,2); row(0,4) = -c123_1[1](0,0)*c123_2[0](0,2)+c123_1[1](0,0)*c123_2[0](2,0)+c123_1[0](0,1)*c123_2[2](0,0)-c123_1[0](0,1)*c123_2[0](2,0)-c123_1[0](1,0)*c123_2[2](0,0)+c123_1[0](1,0)*c123_2[0](0,2); row(0,5) = c123_1[2](0,0)*c123_2[2](1,2)-c123_1[2](0,0)*c123_2[2](2,1)-c123_1[0](0,2)*c123_2[2](1,2)+c123_1[0](0,2)*c123_2[1](2,2)+c123_1[0](2,0)*c123_2[2](2,1)-c123_1[0](2,0)*c123_2[1](2,2); row(0,6) = c123_1[2](0,0)*c123_2[2](0,2)-c123_1[2](0,0)*c123_2[2](2,0)-c123_1[0](0,2)*c123_2[2](0,2)+c123_1[0](0,2)*c123_2[0](2,2)+c123_1[0](2,0)*c123_2[2](2,0)-c123_1[0](2,0)*c123_2[0](2,2); row(0,7) = c123_1[1](0,0)*c123_2[2](1,2)-c123_1[1](0,0)*c123_2[2](2,1)-c123_1[0](0,1)*c123_2[2](1,2)+c123_1[0](0,1)*c123_2[1](2,2)+c123_1[0](1,0)*c123_2[2](2,1)-c123_1[0](1,0)*c123_2[1](2,2); row(0,8) = c123_1[1](0,0)*c123_2[1](1,2)-c123_1[1](0,0)*c123_2[1](2,1)-c123_1[0](0,1)*c123_2[2](1,1)+c123_1[0](0,1)*c123_2[1](2,1)+c123_1[0](1,0)*c123_2[2](1,1)-c123_1[0](1,0)*c123_2[1](1,2); row(0,10) = -c123_1[1](0,0)*c123_2[2](0,1)+c123_1[1](0,0)*c123_2[2](1,0)+c123_1[1](0,0)*c123_2[0](1,2)-c123_1[1](0,0)*c123_2[0](2,1)+c123_1[0](0,1)*c123_2[1](0,2)-c123_1[0](0,1)*c123_2[2](1,0)-c123_1[0](0,1)*c123_2[0](1,2)+c123_1[0](0,1)*c123_2[1](2,0)+c123_1[0](1,0)*c123_2[2](0,1)-c123_1[0](1,0)*c123_2[1](0,2)-c123_1[0](1,0)*c123_2[1](2,0)+c123_1[0](1,0)*c123_2[0](2,1); row(0,11) = -c123_1[1](0,0)*c123_2[1](0,1)+c123_1[1](0,0)*c123_2[1](1,0)+c123_1[0](0,1)*c123_2[1](0,1)-c123_1[0](0,1)*c123_2[0](1,1)-c123_1[0](1,0)*c123_2[1](1,0)+c123_1[0](1,0)*c123_2[0](1,1); row(0,12) = -c123_1[1](0,0)*c123_2[0](0,1)+c123_1[1](0,0)*c123_2[0](1,0)+c123_1[0](0,1)*c123_2[1](0,0)-c123_1[0](0,1)*c123_2[0](1,0)-c123_1[0](1,0)*c123_2[1](0,0)+c123_1[0](1,0)*c123_2[0](0,1); row(0,13) = -c123_1[2](0,0)*c123_2[2](1,2)+c123_1[2](0,0)*c123_2[2](2,1)+c123_1[0](0,2)*c123_2[2](1,2)-c123_1[0](0,2)*c123_2[1](2,2)-c123_1[0](2,0)*c123_2[2](2,1)+c123_1[0](2,0)*c123_2[1](2,2); row(0,14) = c123_1[2](0,0)*c123_2[1](1,2)-c123_1[2](0,0)*c123_2[1](2,1)-c123_1[0](0,2)*c123_2[2](1,1)+c123_1[0](0,2)*c123_2[1](2,1)+c123_1[0](2,0)*c123_2[2](1,1)-c123_1[0](2,0)*c123_2[1](1,2); row(0,15) = c123_1[2](0,0)*c123_2[2](0,1)+c123_1[2](0,0)*c123_2[1](0,2)-c123_1[2](0,0)*c123_2[2](1,0)-c123_1[2](0,0)*c123_2[1](2,0)-c123_1[0](0,2)*c123_2[2](0,1)-c123_1[0](0,2)*c123_2[1](0,2)+c123_1[0](0,2)*c123_2[0](1,2)+c123_1[0](0,2)*c123_2[0](2,1)+c123_1[0](2,0)*c123_2[2](1,0)-c123_1[0](2,0)*c123_2[0](1,2)+c123_1[0](2,0)*c123_2[1](2,0)-c123_1[0](2,0)*c123_2[0](2,1); row(0,16) = -c123_1[2](0,0)*c123_2[1](1,2)+c123_1[2](0,0)*c123_2[1](2,1)+c123_1[0](0,2)*c123_2[2](1,1)-c123_1[0](0,2)*c123_2[1](2,1)-c123_1[0](2,0)*c123_2[2](1,1)+c123_1[0](2,0)*c123_2[1](1,2); row(0,18) = c123_1[2](0,0)*c123_2[1](0,1)-c123_1[2](0,0)*c123_2[1](1,0)-c123_1[0](0,2)*c123_2[1](0,1)+c123_1[0](0,2)*c123_2[0](1,1)+c123_1[0](2,0)*c123_2[1](1,0)-c123_1[0](2,0)*c123_2[0](1,1); row(0,19) = c123_1[1](0,0)*c123_2[2](0,2)-c123_1[1](0,0)*c123_2[2](2,0)-c123_1[0](0,1)*c123_2[2](0,2)+c123_1[0](0,1)*c123_2[0](2,2)+c123_1[0](1,0)*c123_2[2](2,0)-c123_1[0](1,0)*c123_2[0](2,2); row(0,20) = c123_1[1](0,0)*c123_2[2](0,1)+c123_1[1](0,0)*c123_2[1](0,2)-c123_1[1](0,0)*c123_2[2](1,0)-c123_1[1](0,0)*c123_2[1](2,0)-c123_1[0](0,1)*c123_2[2](0,1)-c123_1[0](0,1)*c123_2[1](0,2)+c123_1[0](0,1)*c123_2[0](1,2)+c123_1[0](0,1)*c123_2[0](2,1)+c123_1[0](1,0)*c123_2[2](1,0)-c123_1[0](1,0)*c123_2[0](1,2)+c123_1[0](1,0)*c123_2[1](2,0)-c123_1[0](1,0)*c123_2[0](2,1); row(0,21) = c123_1[1](0,0)*c123_2[1](0,1)-c123_1[1](0,0)*c123_2[1](1,0)-c123_1[0](0,1)*c123_2[1](0,1)+c123_1[0](0,1)*c123_2[0](1,1)+c123_1[0](1,0)*c123_2[1](1,0)-c123_1[0](1,0)*c123_2[0](1,1); row(0,22) = c123_1[1](0,0)*c123_2[0](0,2)-c123_1[1](0,0)*c123_2[0](2,0)-c123_1[0](0,1)*c123_2[2](0,0)+c123_1[0](0,1)*c123_2[0](2,0)+c123_1[0](1,0)*c123_2[2](0,0)-c123_1[0](1,0)*c123_2[0](0,2); row(0,23) = c123_1[1](0,0)*c123_2[0](0,1)-c123_1[1](0,0)*c123_2[0](1,0)-c123_1[0](0,1)*c123_2[1](0,0)+c123_1[0](0,1)*c123_2[0](1,0)+c123_1[0](1,0)*c123_2[1](0,0)-c123_1[0](1,0)*c123_2[0](0,1); row(0,25) = -c123_1[2](0,0)*c123_2[2](0,2)+c123_1[2](0,0)*c123_2[2](2,0)+c123_1[0](0,2)*c123_2[2](0,2)-c123_1[0](0,2)*c123_2[0](2,2)-c123_1[0](2,0)*c123_2[2](2,0)+c123_1[0](2,0)*c123_2[0](2,2); row(0,26) = -c123_1[2](0,0)*c123_2[2](0,1)+c123_1[2](0,0)*c123_2[2](1,0)+c123_1[2](0,0)*c123_2[0](1,2)-c123_1[2](0,0)*c123_2[0](2,1)+c123_1[0](0,2)*c123_2[1](0,2)-c123_1[0](0,2)*c123_2[2](1,0)-c123_1[0](0,2)*c123_2[0](1,2)+c123_1[0](0,2)*c123_2[1](2,0)+c123_1[0](2,0)*c123_2[2](0,1)-c123_1[0](2,0)*c123_2[1](0,2)-c123_1[0](2,0)*c123_2[1](2,0)+c123_1[0](2,0)*c123_2[0](2,1); row(0,27) = c123_1[2](0,0)*c123_2[0](0,2)-c123_1[2](0,0)*c123_2[0](2,0)-c123_1[0](0,2)*c123_2[2](0,0)+c123_1[0](0,2)*c123_2[0](2,0)+c123_1[0](2,0)*c123_2[2](0,0)-c123_1[0](2,0)*c123_2[0](0,2); row(0,28) = -c123_1[2](0,0)*c123_2[1](0,2)-c123_1[2](0,0)*c123_2[0](1,2)+c123_1[2](0,0)*c123_2[1](2,0)+c123_1[2](0,0)*c123_2[0](2,1)+c123_1[0](0,2)*c123_2[2](0,1)+c123_1[0](0,2)*c123_2[2](1,0)-c123_1[0](0,2)*c123_2[1](2,0)-c123_1[0](0,2)*c123_2[0](2,1)-c123_1[0](2,0)*c123_2[2](0,1)+c123_1[0](2,0)*c123_2[1](0,2)-c123_1[0](2,0)*c123_2[2](1,0)+c123_1[0](2,0)*c123_2[0](1,2); row(0,29) = -c123_1[2](0,0)*c123_2[1](0,1)+c123_1[2](0,0)*c123_2[1](1,0)+c123_1[0](0,2)*c123_2[1](0,1)-c123_1[0](0,2)*c123_2[0](1,1)-c123_1[0](2,0)*c123_2[1](1,0)+c123_1[0](2,0)*c123_2[0](1,1); row(0,30) = c123_1[2](0,0)*c123_2[0](0,1)-c123_1[2](0,0)*c123_2[0](1,0)-c123_1[0](0,2)*c123_2[1](0,0)+c123_1[0](0,2)*c123_2[0](1,0)+c123_1[0](2,0)*c123_2[1](0,0)-c123_1[0](2,0)*c123_2[0](0,1); row(0,33) = -c123_1[2](0,0)*c123_2[0](0,2)+c123_1[2](0,0)*c123_2[0](2,0)+c123_1[0](0,2)*c123_2[2](0,0)-c123_1[0](0,2)*c123_2[0](2,0)-c123_1[0](2,0)*c123_2[2](0,0)+c123_1[0](2,0)*c123_2[0](0,2); row(0,34) = -c123_1[2](0,0)*c123_2[0](0,1)+c123_1[2](0,0)*c123_2[0](1,0)+c123_1[0](0,2)*c123_2[1](0,0)-c123_1[0](0,2)*c123_2[0](1,0)-c123_1[0](2,0)*c123_2[1](0,0)+c123_1[0](2,0)*c123_2[0](0,1); row(0,39) = -c123_1[1](0,1)*c123_2[2](2,1)+c123_1[1](0,1)*c123_2[1](2,2)+c123_1[1](1,0)*c123_2[2](1,2)-c123_1[1](1,0)*c123_2[1](2,2)-c123_1[0](1,1)*c123_2[2](1,2)+c123_1[0](1,1)*c123_2[2](2,1); row(0,40) = -c123_1[1](0,1)*c123_2[2](1,1)+c123_1[1](0,1)*c123_2[1](1,2)+c123_1[1](1,0)*c123_2[2](1,1)-c123_1[1](1,0)*c123_2[1](2,1)-c123_1[0](1,1)*c123_2[1](1,2)+c123_1[0](1,1)*c123_2[1](2,1); row(0,41) = -c123_1[1](0,1)*c123_2[2](2,0)+c123_1[1](0,1)*c123_2[0](2,2)+c123_1[1](1,0)*c123_2[2](0,2)-c123_1[1](1,0)*c123_2[0](2,2)-c123_1[0](1,1)*c123_2[2](0,2)+c123_1[0](1,1)*c123_2[2](2,0); row(0,42) = -c123_1[1](0,1)*c123_2[2](0,1)+c123_1[1](0,1)*c123_2[1](0,2)-c123_1[1](0,1)*c123_2[2](1,0)+c123_1[1](0,1)*c123_2[0](1,2)+c123_1[1](1,0)*c123_2[2](0,1)+c123_1[1](1,0)*c123_2[2](1,0)-c123_1[1](1,0)*c123_2[1](2,0)-c123_1[1](1,0)*c123_2[0](2,1)-c123_1[0](1,1)*c123_2[1](0,2)-c123_1[0](1,1)*c123_2[0](1,2)+c123_1[0](1,1)*c123_2[1](2,0)+c123_1[0](1,1)*c123_2[0](2,1); row(0,43) = -c123_1[1](0,1)*c123_2[2](0,0)+c123_1[1](0,1)*c123_2[0](0,2)+c123_1[1](1,0)*c123_2[2](0,0)-c123_1[1](1,0)*c123_2[0](2,0)-c123_1[0](1,1)*c123_2[0](0,2)+c123_1[0](1,1)*c123_2[0](2,0); row(0,44) = -c123_1[2](0,1)*c123_2[2](1,2)+c123_1[2](0,1)*c123_2[2](2,1)+c123_1[1](0,2)*c123_2[2](1,2)-c123_1[1](0,2)*c123_2[1](2,2)-c123_1[2](1,0)*c123_2[2](1,2)+c123_1[2](1,0)*c123_2[2](2,1)+c123_1[0](1,2)*c123_2[2](1,2)-c123_1[0](1,2)*c123_2[1](2,2)-c123_1[1](2,0)*c123_2[2](2,1)+c123_1[1](2,0)*c123_2[1](2,2)-c123_1[0](2,1)*c123_2[2](2,1)+c123_1[0](2,1)*c123_2[1](2,2); row(0,45) = -c123_1[2](0,1)*c123_2[2](0,2)+c123_1[2](0,1)*c123_2[2](2,0)+c123_1[1](0,2)*c123_2[2](0,2)-c123_1[1](0,2)*c123_2[0](2,2)-c123_1[2](1,0)*c123_2[2](0,2)+c123_1[2](1,0)*c123_2[2](2,0)+c123_1[0](1,2)*c123_2[2](0,2)-c123_1[0](1,2)*c123_2[0](2,2)-c123_1[1](2,0)*c123_2[2](2,0)+c123_1[1](2,0)*c123_2[0](2,2)-c123_1[0](2,1)*c123_2[2](2,0)+c123_1[0](2,1)*c123_2[0](2,2); row(0,46) = c123_1[2](0,1)*c123_2[2](1,2)-c123_1[2](0,1)*c123_2[1](2,2)-c123_1[1](0,2)*c123_2[2](1,2)+c123_1[1](0,2)*c123_2[2](2,1)-c123_1[2](1,0)*c123_2[2](2,1)+c123_1[2](1,0)*c123_2[1](2,2)-c123_1[0](1,2)*c123_2[2](2,1)+c123_1[0](1,2)*c123_2[1](2,2)-c123_1[1](2,0)*c123_2[2](1,2)+c123_1[1](2,0)*c123_2[2](2,1)+c123_1[0](2,1)*c123_2[2](1,2)-c123_1[0](2,1)*c123_2[1](2,2); row(0,47) = c123_1[2](0,1)*c123_2[2](1,1)-c123_1[2](0,1)*c123_2[1](1,2)+c123_1[1](0,2)*c123_2[2](1,1)-c123_1[1](0,2)*c123_2[1](1,2)-c123_1[2](1,0)*c123_2[2](1,1)+c123_1[2](1,0)*c123_2[1](2,1)+c123_1[0](1,2)*c123_2[1](1,2)-c123_1[0](1,2)*c123_2[1](2,1)-c123_1[1](2,0)*c123_2[2](1,1)+c123_1[1](2,0)*c123_2[1](2,1)+c123_1[0](2,1)*c123_2[1](1,2)-c123_1[0](2,1)*c123_2[1](2,1); row(0,48) = -c123_1[2](0,1)*c123_2[1](0,2)+c123_1[2](0,1)*c123_2[2](1,0)+c123_1[1](0,2)*c123_2[2](0,1)-c123_1[1](0,2)*c123_2[0](1,2)-c123_1[2](1,0)*c123_2[2](0,1)+c123_1[2](1,0)*c123_2[1](2,0)+c123_1[0](1,2)*c123_2[1](0,2)-c123_1[0](1,2)*c123_2[0](2,1)-c123_1[1](2,0)*c123_2[2](1,0)+c123_1[1](2,0)*c123_2[0](2,1)+c123_1[0](2,1)*c123_2[0](1,2)-c123_1[0](2,1)*c123_2[1](2,0); row(0,49) = -c123_1[2](0,2)*c123_2[2](2,1)+c123_1[2](0,2)*c123_2[1](2,2)+c123_1[2](2,0)*c123_2[2](1,2)-c123_1[2](2,0)*c123_2[1](2,2)-c123_1[0](2,2)*c123_2[2](1,2)+c123_1[0](2,2)*c123_2[2](2,1); row(0,50) = -c123_1[2](0,2)*c123_2[2](1,1)+c123_1[2](0,2)*c123_2[1](1,2)+c123_1[2](2,0)*c123_2[2](1,1)-c123_1[2](2,0)*c123_2[1](2,1)-c123_1[0](2,2)*c123_2[1](1,2)+c123_1[0](2,2)*c123_2[1](2,1); row(0,51) = c123_1[2](0,1)*c123_2[2](0,2)-c123_1[2](0,1)*c123_2[0](2,2)-c123_1[1](0,2)*c123_2[2](0,2)+c123_1[1](0,2)*c123_2[2](2,0)-c123_1[2](1,0)*c123_2[2](2,0)+c123_1[2](1,0)*c123_2[0](2,2)-c123_1[0](1,2)*c123_2[2](2,0)+c123_1[0](1,2)*c123_2[0](2,2)-c123_1[1](2,0)*c123_2[2](0,2)+c123_1[1](2,0)*c123_2[2](2,0)+c123_1[0](2,1)*c123_2[2](0,2)-c123_1[0](2,1)*c123_2[0](2,2); row(0,52) = c123_1[2](0,1)*c123_2[2](0,1)-c123_1[2](0,1)*c123_2[0](1,2)-c123_1[1](0,2)*c123_2[1](0,2)+c123_1[1](0,2)*c123_2[2](1,0)-c123_1[2](1,0)*c123_2[2](1,0)+c123_1[2](1,0)*c123_2[0](2,1)+c123_1[0](1,2)*c123_2[0](1,2)-c123_1[0](1,2)*c123_2[1](2,0)-c123_1[1](2,0)*c123_2[2](0,1)+c123_1[1](2,0)*c123_2[1](2,0)+c123_1[0](2,1)*c123_2[1](0,2)-c123_1[0](2,1)*c123_2[0](2,1); row(0,53) = c123_1[2](0,1)*c123_2[2](0,0)-c123_1[2](0,1)*c123_2[0](0,2)+c123_1[1](0,2)*c123_2[2](0,0)-c123_1[1](0,2)*c123_2[0](0,2)-c123_1[2](1,0)*c123_2[2](0,0)+c123_1[2](1,0)*c123_2[0](2,0)+c123_1[0](1,2)*c123_2[0](0,2)-c123_1[0](1,2)*c123_2[0](2,0)-c123_1[1](2,0)*c123_2[2](0,0)+c123_1[1](2,0)*c123_2[0](2,0)+c123_1[0](2,1)*c123_2[0](0,2)-c123_1[0](2,1)*c123_2[0](2,0); row(0,54) = -c123_1[2](0,2)*c123_2[2](2,0)+c123_1[2](0,2)*c123_2[0](2,2)+c123_1[2](2,0)*c123_2[2](0,2)-c123_1[2](2,0)*c123_2[0](2,2)-c123_1[0](2,2)*c123_2[2](0,2)+c123_1[0](2,2)*c123_2[2](2,0); row(0,55) = -c123_1[2](0,2)*c123_2[2](0,1)+c123_1[2](0,2)*c123_2[1](0,2)-c123_1[2](0,2)*c123_2[2](1,0)+c123_1[2](0,2)*c123_2[0](1,2)+c123_1[2](2,0)*c123_2[2](0,1)+c123_1[2](2,0)*c123_2[2](1,0)-c123_1[2](2,0)*c123_2[1](2,0)-c123_1[2](2,0)*c123_2[0](2,1)-c123_1[0](2,2)*c123_2[1](0,2)-c123_1[0](2,2)*c123_2[0](1,2)+c123_1[0](2,2)*c123_2[1](2,0)+c123_1[0](2,2)*c123_2[0](2,1); row(0,56) = -c123_1[2](0,2)*c123_2[2](0,0)+c123_1[2](0,2)*c123_2[0](0,2)+c123_1[2](2,0)*c123_2[2](0,0)-c123_1[2](2,0)*c123_2[0](2,0)-c123_1[0](2,2)*c123_2[0](0,2)+c123_1[0](2,2)*c123_2[0](2,0); row(0,57) = c123_1[2](1,1)*c123_2[2](1,2)-c123_1[2](1,1)*c123_2[2](2,1)-c123_1[1](1,2)*c123_2[2](1,2)+c123_1[1](1,2)*c123_2[1](2,2)+c123_1[1](2,1)*c123_2[2](2,1)-c123_1[1](2,1)*c123_2[1](2,2); row(0,58) = c123_1[2](1,1)*c123_2[2](0,2)-c123_1[2](1,1)*c123_2[2](2,0)-c123_1[1](1,2)*c123_2[2](0,2)+c123_1[1](1,2)*c123_2[0](2,2)+c123_1[1](2,1)*c123_2[2](2,0)-c123_1[1](2,1)*c123_2[0](2,2); row(0,59) = c123_1[2](1,2)*c123_2[2](2,1)-c123_1[2](1,2)*c123_2[1](2,2)-c123_1[2](2,1)*c123_2[2](1,2)+c123_1[2](2,1)*c123_2[1](2,2)+c123_1[1](2,2)*c123_2[2](1,2)-c123_1[1](2,2)*c123_2[2](2,1); row(0,60) = c123_1[2](1,2)*c123_2[2](2,0)-c123_1[2](1,2)*c123_2[0](2,2)-c123_1[2](2,1)*c123_2[2](0,2)+c123_1[2](2,1)*c123_2[0](2,2)+c123_1[1](2,2)*c123_2[2](0,2)-c123_1[1](2,2)*c123_2[2](2,0); row(0,61) = c123_1[1](0,1)*c123_2[2](2,1)-c123_1[1](0,1)*c123_2[1](2,2)-c123_1[1](1,0)*c123_2[2](1,2)+c123_1[1](1,0)*c123_2[1](2,2)+c123_1[0](1,1)*c123_2[2](1,2)-c123_1[0](1,1)*c123_2[2](2,1); row(0,62) = c123_1[1](0,1)*c123_2[2](1,1)-c123_1[1](0,1)*c123_2[1](1,2)-c123_1[1](1,0)*c123_2[2](1,1)+c123_1[1](1,0)*c123_2[1](2,1)+c123_1[0](1,1)*c123_2[1](1,2)-c123_1[0](1,1)*c123_2[1](2,1); row(0,64) = c123_1[1](0,1)*c123_2[2](0,1)-c123_1[1](0,1)*c123_2[1](0,2)-c123_1[1](0,1)*c123_2[1](2,0)+c123_1[1](0,1)*c123_2[0](2,1)+c123_1[1](1,0)*c123_2[1](0,2)-c123_1[1](1,0)*c123_2[2](1,0)-c123_1[1](1,0)*c123_2[0](1,2)+c123_1[1](1,0)*c123_2[1](2,0)-c123_1[0](1,1)*c123_2[2](0,1)+c123_1[0](1,1)*c123_2[2](1,0)+c123_1[0](1,1)*c123_2[0](1,2)-c123_1[0](1,1)*c123_2[0](2,1); row(0,65) = -c123_1[1](0,1)*c123_2[1](1,0)+c123_1[1](0,1)*c123_2[0](1,1)+c123_1[1](1,0)*c123_2[1](0,1)-c123_1[1](1,0)*c123_2[0](1,1)-c123_1[0](1,1)*c123_2[1](0,1)+c123_1[0](1,1)*c123_2[1](1,0); row(0,66) = -c123_1[1](0,1)*c123_2[1](0,0)+c123_1[1](0,1)*c123_2[0](0,1)+c123_1[1](1,0)*c123_2[1](0,0)-c123_1[1](1,0)*c123_2[0](1,0)-c123_1[0](1,1)*c123_2[0](0,1)+c123_1[0](1,1)*c123_2[0](1,0); row(0,67) = -c123_1[2](0,1)*c123_2[2](2,1)+c123_1[2](0,1)*c123_2[1](2,2)-c123_1[1](0,2)*c123_2[2](2,1)+c123_1[1](0,2)*c123_2[1](2,2)+c123_1[2](1,0)*c123_2[2](1,2)-c123_1[2](1,0)*c123_2[1](2,2)-c123_1[0](1,2)*c123_2[2](1,2)+c123_1[0](1,2)*c123_2[2](2,1)+c123_1[1](2,0)*c123_2[2](1,2)-c123_1[1](2,0)*c123_2[1](2,2)-c123_1[0](2,1)*c123_2[2](1,2)+c123_1[0](2,1)*c123_2[2](2,1); row(0,68) = -c123_1[2](0,1)*c123_2[2](1,1)+c123_1[2](0,1)*c123_2[1](2,1)+c123_1[1](0,2)*c123_2[1](1,2)-c123_1[1](0,2)*c123_2[1](2,1)+c123_1[2](1,0)*c123_2[2](1,1)-c123_1[2](1,0)*c123_2[1](1,2)+c123_1[0](1,2)*c123_2[2](1,1)-c123_1[0](1,2)*c123_2[1](1,2)+c123_1[1](2,0)*c123_2[1](1,2)-c123_1[1](2,0)*c123_2[1](2,1)-c123_1[0](2,1)*c123_2[2](1,1)+c123_1[0](2,1)*c123_2[1](2,1); row(0,69) = -c123_1[2](0,1)*c123_2[2](0,1)+c123_1[2](0,1)*c123_2[1](2,0)+c123_1[1](0,2)*c123_2[1](0,2)-c123_1[1](0,2)*c123_2[0](2,1)-c123_1[2](1,0)*c123_2[1](0,2)+c123_1[2](1,0)*c123_2[2](1,0)+c123_1[0](1,2)*c123_2[2](0,1)-c123_1[0](1,2)*c123_2[0](1,2)+c123_1[1](2,0)*c123_2[0](1,2)-c123_1[1](2,0)*c123_2[1](2,0)-c123_1[0](2,1)*c123_2[2](1,0)+c123_1[0](2,1)*c123_2[0](2,1); row(0,70) = c123_1[2](0,2)*c123_2[2](2,1)-c123_1[2](0,2)*c123_2[1](2,2)-c123_1[2](2,0)*c123_2[2](1,2)+c123_1[2](2,0)*c123_2[1](2,2)+c123_1[0](2,2)*c123_2[2](1,2)-c123_1[0](2,2)*c123_2[2](2,1); row(0,71) = c123_1[2](0,1)*c123_2[1](1,2)-c123_1[2](0,1)*c123_2[1](2,1)-c123_1[1](0,2)*c123_2[2](1,1)+c123_1[1](0,2)*c123_2[1](2,1)+c123_1[2](1,0)*c123_2[1](1,2)-c123_1[2](1,0)*c123_2[1](2,1)-c123_1[0](1,2)*c123_2[2](1,1)+c123_1[0](1,2)*c123_2[1](2,1)+c123_1[1](2,0)*c123_2[2](1,1)-c123_1[1](2,0)*c123_2[1](1,2)+c123_1[0](2,1)*c123_2[2](1,1)-c123_1[0](2,1)*c123_2[1](1,2); row(0,73) = -c123_1[2](0,1)*c123_2[1](0,1)+c123_1[2](0,1)*c123_2[1](1,0)+c123_1[1](0,2)*c123_2[1](0,1)-c123_1[1](0,2)*c123_2[0](1,1)-c123_1[2](1,0)*c123_2[1](0,1)+c123_1[2](1,0)*c123_2[1](1,0)+c123_1[0](1,2)*c123_2[1](0,1)-c123_1[0](1,2)*c123_2[0](1,1)-c123_1[1](2,0)*c123_2[1](1,0)+c123_1[1](2,0)*c123_2[0](1,1)-c123_1[0](2,1)*c123_2[1](1,0)+c123_1[0](2,1)*c123_2[0](1,1); row(0,74) = c123_1[2](0,2)*c123_2[2](1,1)-c123_1[2](0,2)*c123_2[1](1,2)-c123_1[2](2,0)*c123_2[2](1,1)+c123_1[2](2,0)*c123_2[1](2,1)+c123_1[0](2,2)*c123_2[1](1,2)-c123_1[0](2,2)*c123_2[1](2,1); row(0,76) = c123_1[2](0,1)*c123_2[1](0,2)-c123_1[2](0,1)*c123_2[0](2,1)-c123_1[1](0,2)*c123_2[2](0,1)+c123_1[1](0,2)*c123_2[1](2,0)+c123_1[2](1,0)*c123_2[0](1,2)-c123_1[2](1,0)*c123_2[1](2,0)-c123_1[0](1,2)*c123_2[2](1,0)+c123_1[0](1,2)*c123_2[0](2,1)-c123_1[1](2,0)*c123_2[1](0,2)+c123_1[1](2,0)*c123_2[2](1,0)+c123_1[0](2,1)*c123_2[2](0,1)-c123_1[0](2,1)*c123_2[0](1,2); row(0,77) = c123_1[2](0,1)*c123_2[1](0,1)-c123_1[2](0,1)*c123_2[0](1,1)-c123_1[1](0,2)*c123_2[1](0,1)+c123_1[1](0,2)*c123_2[1](1,0)-c123_1[2](1,0)*c123_2[1](1,0)+c123_1[2](1,0)*c123_2[0](1,1)-c123_1[0](1,2)*c123_2[1](1,0)+c123_1[0](1,2)*c123_2[0](1,1)-c123_1[1](2,0)*c123_2[1](0,1)+c123_1[1](2,0)*c123_2[1](1,0)+c123_1[0](2,1)*c123_2[1](0,1)-c123_1[0](2,1)*c123_2[0](1,1); row(0,78) = c123_1[2](0,1)*c123_2[1](0,0)-c123_1[2](0,1)*c123_2[0](0,1)+c123_1[1](0,2)*c123_2[1](0,0)-c123_1[1](0,2)*c123_2[0](0,1)-c123_1[2](1,0)*c123_2[1](0,0)+c123_1[2](1,0)*c123_2[0](1,0)+c123_1[0](1,2)*c123_2[0](0,1)-c123_1[0](1,2)*c123_2[0](1,0)-c123_1[1](2,0)*c123_2[1](0,0)+c123_1[1](2,0)*c123_2[0](1,0)+c123_1[0](2,1)*c123_2[0](0,1)-c123_1[0](2,1)*c123_2[0](1,0); row(0,79) = c123_1[2](0,2)*c123_2[2](0,1)-c123_1[2](0,2)*c123_2[1](0,2)-c123_1[2](0,2)*c123_2[1](2,0)+c123_1[2](0,2)*c123_2[0](2,1)+c123_1[2](2,0)*c123_2[1](0,2)-c123_1[2](2,0)*c123_2[2](1,0)-c123_1[2](2,0)*c123_2[0](1,2)+c123_1[2](2,0)*c123_2[1](2,0)-c123_1[0](2,2)*c123_2[2](0,1)+c123_1[0](2,2)*c123_2[2](1,0)+c123_1[0](2,2)*c123_2[0](1,2)-c123_1[0](2,2)*c123_2[0](2,1); row(0,80) = -c123_1[2](0,2)*c123_2[1](1,0)+c123_1[2](0,2)*c123_2[0](1,1)+c123_1[2](2,0)*c123_2[1](0,1)-c123_1[2](2,0)*c123_2[0](1,1)-c123_1[0](2,2)*c123_2[1](0,1)+c123_1[0](2,2)*c123_2[1](1,0); row(0,81) = c123_1[2](0,2)*c123_2[0](0,1)-c123_1[2](0,2)*c123_2[1](0,0)+c123_1[2](2,0)*c123_2[1](0,0)-c123_1[2](2,0)*c123_2[0](1,0)-c123_1[0](2,2)*c123_2[0](0,1)+c123_1[0](2,2)*c123_2[0](1,0); row(0,82) = -c123_1[2](1,1)*c123_2[2](1,2)+c123_1[2](1,1)*c123_2[2](2,1)+c123_1[1](1,2)*c123_2[2](1,2)-c123_1[1](1,2)*c123_2[1](2,2)-c123_1[1](2,1)*c123_2[2](2,1)+c123_1[1](2,1)*c123_2[1](2,2); row(0,83) = c123_1[2](1,1)*c123_2[1](1,2)-c123_1[2](1,1)*c123_2[1](2,1)-c123_1[1](1,2)*c123_2[2](1,1)+c123_1[1](1,2)*c123_2[1](2,1)+c123_1[1](2,1)*c123_2[2](1,1)-c123_1[1](2,1)*c123_2[1](1,2); row(0,84) = c123_1[2](1,1)*c123_2[2](0,1)+c123_1[2](1,1)*c123_2[1](0,2)-c123_1[2](1,1)*c123_2[2](1,0)-c123_1[2](1,1)*c123_2[1](2,0)-c123_1[1](1,2)*c123_2[2](0,1)-c123_1[1](1,2)*c123_2[1](0,2)+c123_1[1](1,2)*c123_2[0](1,2)+c123_1[1](1,2)*c123_2[0](2,1)+c123_1[1](2,1)*c123_2[2](1,0)-c123_1[1](2,1)*c123_2[0](1,2)+c123_1[1](2,1)*c123_2[1](2,0)-c123_1[1](2,1)*c123_2[0](2,1); row(0,85) = -c123_1[2](1,2)*c123_2[2](2,1)+c123_1[2](1,2)*c123_2[1](2,2)+c123_1[2](2,1)*c123_2[2](1,2)-c123_1[2](2,1)*c123_2[1](2,2)-c123_1[1](2,2)*c123_2[2](1,2)+c123_1[1](2,2)*c123_2[2](2,1); row(0,86) = c123_1[2](1,2)*c123_2[2](1,1)-c123_1[2](1,2)*c123_2[1](1,2)-c123_1[2](2,1)*c123_2[2](1,1)+c123_1[2](2,1)*c123_2[1](2,1)+c123_1[1](2,2)*c123_2[1](1,2)-c123_1[1](2,2)*c123_2[1](2,1); row(0,87) = c123_1[2](1,2)*c123_2[2](1,0)-c123_1[2](1,2)*c123_2[0](1,2)+c123_1[2](1,2)*c123_2[1](2,0)-c123_1[2](1,2)*c123_2[0](2,1)-c123_1[2](2,1)*c123_2[2](0,1)-c123_1[2](2,1)*c123_2[1](0,2)+c123_1[2](2,1)*c123_2[0](1,2)+c123_1[2](2,1)*c123_2[0](2,1)+c123_1[1](2,2)*c123_2[2](0,1)+c123_1[1](2,2)*c123_2[1](0,2)-c123_1[1](2,2)*c123_2[2](1,0)-c123_1[1](2,2)*c123_2[1](2,0); row(0,89) = -c123_1[2](1,1)*c123_2[1](1,2)+c123_1[2](1,1)*c123_2[1](2,1)+c123_1[1](1,2)*c123_2[2](1,1)-c123_1[1](1,2)*c123_2[1](2,1)-c123_1[1](2,1)*c123_2[2](1,1)+c123_1[1](2,1)*c123_2[1](1,2); row(0,91) = c123_1[2](1,1)*c123_2[1](0,1)-c123_1[2](1,1)*c123_2[1](1,0)-c123_1[1](1,2)*c123_2[1](0,1)+c123_1[1](1,2)*c123_2[0](1,1)+c123_1[1](2,1)*c123_2[1](1,0)-c123_1[1](2,1)*c123_2[0](1,1); row(0,92) = -c123_1[2](1,2)*c123_2[2](1,1)+c123_1[2](1,2)*c123_2[1](1,2)+c123_1[2](2,1)*c123_2[2](1,1)-c123_1[2](2,1)*c123_2[1](2,1)-c123_1[1](2,2)*c123_2[1](1,2)+c123_1[1](2,2)*c123_2[1](2,1); row(0,94) = c123_1[2](1,2)*c123_2[1](1,0)-c123_1[2](1,2)*c123_2[0](1,1)-c123_1[2](2,1)*c123_2[1](0,1)+c123_1[2](2,1)*c123_2[0](1,1)+c123_1[1](2,2)*c123_2[1](0,1)-c123_1[1](2,2)*c123_2[1](1,0); row(0,97) = c123_1[1](0,1)*c123_2[2](2,0)-c123_1[1](0,1)*c123_2[0](2,2)-c123_1[1](1,0)*c123_2[2](0,2)+c123_1[1](1,0)*c123_2[0](2,2)+c123_1[0](1,1)*c123_2[2](0,2)-c123_1[0](1,1)*c123_2[2](2,0); row(0,98) = c123_1[1](0,1)*c123_2[2](1,0)-c123_1[1](0,1)*c123_2[0](1,2)+c123_1[1](0,1)*c123_2[1](2,0)-c123_1[1](0,1)*c123_2[0](2,1)-c123_1[1](1,0)*c123_2[2](0,1)-c123_1[1](1,0)*c123_2[1](0,2)+c123_1[1](1,0)*c123_2[0](1,2)+c123_1[1](1,0)*c123_2[0](2,1)+c123_1[0](1,1)*c123_2[2](0,1)+c123_1[0](1,1)*c123_2[1](0,2)-c123_1[0](1,1)*c123_2[2](1,0)-c123_1[0](1,1)*c123_2[1](2,0); row(0,99) = c123_1[1](0,1)*c123_2[1](1,0)-c123_1[1](0,1)*c123_2[0](1,1)-c123_1[1](1,0)*c123_2[1](0,1)+c123_1[1](1,0)*c123_2[0](1,1)+c123_1[0](1,1)*c123_2[1](0,1)-c123_1[0](1,1)*c123_2[1](1,0); row(0,100) = c123_1[1](0,1)*c123_2[2](0,0)-c123_1[1](0,1)*c123_2[0](0,2)-c123_1[1](1,0)*c123_2[2](0,0)+c123_1[1](1,0)*c123_2[0](2,0)+c123_1[0](1,1)*c123_2[0](0,2)-c123_1[0](1,1)*c123_2[0](2,0); row(0,101) = c123_1[1](0,1)*c123_2[1](0,0)-c123_1[1](0,1)*c123_2[0](0,1)-c123_1[1](1,0)*c123_2[1](0,0)+c123_1[1](1,0)*c123_2[0](1,0)+c123_1[0](1,1)*c123_2[0](0,1)-c123_1[0](1,1)*c123_2[0](1,0); row(0,103) = -c123_1[2](0,1)*c123_2[2](2,0)+c123_1[2](0,1)*c123_2[0](2,2)-c123_1[1](0,2)*c123_2[2](2,0)+c123_1[1](0,2)*c123_2[0](2,2)+c123_1[2](1,0)*c123_2[2](0,2)-c123_1[2](1,0)*c123_2[0](2,2)-c123_1[0](1,2)*c123_2[2](0,2)+c123_1[0](1,2)*c123_2[2](2,0)+c123_1[1](2,0)*c123_2[2](0,2)-c123_1[1](2,0)*c123_2[0](2,2)-c123_1[0](2,1)*c123_2[2](0,2)+c123_1[0](2,1)*c123_2[2](2,0); row(0,104) = -c123_1[2](0,1)*c123_2[2](1,0)+c123_1[2](0,1)*c123_2[0](2,1)+c123_1[1](0,2)*c123_2[0](1,2)-c123_1[1](0,2)*c123_2[1](2,0)+c123_1[2](1,0)*c123_2[2](0,1)-c123_1[2](1,0)*c123_2[0](1,2)-c123_1[0](1,2)*c123_2[1](0,2)+c123_1[0](1,2)*c123_2[2](1,0)+c123_1[1](2,0)*c123_2[1](0,2)-c123_1[1](2,0)*c123_2[0](2,1)-c123_1[0](2,1)*c123_2[2](0,1)+c123_1[0](2,1)*c123_2[1](2,0); row(0,105) = -c123_1[2](0,1)*c123_2[2](0,0)+c123_1[2](0,1)*c123_2[0](2,0)+c123_1[1](0,2)*c123_2[0](0,2)-c123_1[1](0,2)*c123_2[0](2,0)+c123_1[2](1,0)*c123_2[2](0,0)-c123_1[2](1,0)*c123_2[0](0,2)+c123_1[0](1,2)*c123_2[2](0,0)-c123_1[0](1,2)*c123_2[0](0,2)+c123_1[1](2,0)*c123_2[0](0,2)-c123_1[1](2,0)*c123_2[0](2,0)-c123_1[0](2,1)*c123_2[2](0,0)+c123_1[0](2,1)*c123_2[0](2,0); row(0,106) = c123_1[2](0,2)*c123_2[2](2,0)-c123_1[2](0,2)*c123_2[0](2,2)-c123_1[2](2,0)*c123_2[2](0,2)+c123_1[2](2,0)*c123_2[0](2,2)+c123_1[0](2,2)*c123_2[2](0,2)-c123_1[0](2,2)*c123_2[2](2,0); row(0,107) = c123_1[2](0,1)*c123_2[0](1,2)-c123_1[2](0,1)*c123_2[1](2,0)-c123_1[1](0,2)*c123_2[2](1,0)+c123_1[1](0,2)*c123_2[0](2,1)+c123_1[2](1,0)*c123_2[1](0,2)-c123_1[2](1,0)*c123_2[0](2,1)-c123_1[0](1,2)*c123_2[2](0,1)+c123_1[0](1,2)*c123_2[1](2,0)+c123_1[1](2,0)*c123_2[2](0,1)-c123_1[1](2,0)*c123_2[0](1,2)-c123_1[0](2,1)*c123_2[1](0,2)+c123_1[0](2,1)*c123_2[2](1,0); row(0,108) = -c123_1[2](0,1)*c123_2[1](1,0)+c123_1[2](0,1)*c123_2[0](1,1)-c123_1[1](0,2)*c123_2[1](1,0)+c123_1[1](0,2)*c123_2[0](1,1)+c123_1[2](1,0)*c123_2[1](0,1)-c123_1[2](1,0)*c123_2[0](1,1)-c123_1[0](1,2)*c123_2[1](0,1)+c123_1[0](1,2)*c123_2[1](1,0)+c123_1[1](2,0)*c123_2[1](0,1)-c123_1[1](2,0)*c123_2[0](1,1)-c123_1[0](2,1)*c123_2[1](0,1)+c123_1[0](2,1)*c123_2[1](1,0); row(0,109) = -c123_1[2](0,1)*c123_2[1](0,0)+c123_1[2](0,1)*c123_2[0](1,0)+c123_1[1](0,2)*c123_2[0](0,1)-c123_1[1](0,2)*c123_2[0](1,0)+c123_1[2](1,0)*c123_2[1](0,0)-c123_1[2](1,0)*c123_2[0](0,1)+c123_1[0](1,2)*c123_2[1](0,0)-c123_1[0](1,2)*c123_2[0](0,1)+c123_1[1](2,0)*c123_2[0](0,1)-c123_1[1](2,0)*c123_2[0](1,0)-c123_1[0](2,1)*c123_2[1](0,0)+c123_1[0](2,1)*c123_2[0](1,0); row(0,110) = c123_1[2](0,2)*c123_2[2](1,0)-c123_1[2](0,2)*c123_2[0](1,2)+c123_1[2](0,2)*c123_2[1](2,0)-c123_1[2](0,2)*c123_2[0](2,1)-c123_1[2](2,0)*c123_2[2](0,1)-c123_1[2](2,0)*c123_2[1](0,2)+c123_1[2](2,0)*c123_2[0](1,2)+c123_1[2](2,0)*c123_2[0](2,1)+c123_1[0](2,2)*c123_2[2](0,1)+c123_1[0](2,2)*c123_2[1](0,2)-c123_1[0](2,2)*c123_2[2](1,0)-c123_1[0](2,2)*c123_2[1](2,0); row(0,111) = c123_1[2](0,2)*c123_2[1](1,0)-c123_1[2](0,2)*c123_2[0](1,1)-c123_1[2](2,0)*c123_2[1](0,1)+c123_1[2](2,0)*c123_2[0](1,1)+c123_1[0](2,2)*c123_2[1](0,1)-c123_1[0](2,2)*c123_2[1](1,0); row(0,112) = c123_1[2](0,1)*c123_2[0](0,2)-c123_1[2](0,1)*c123_2[0](2,0)-c123_1[1](0,2)*c123_2[2](0,0)+c123_1[1](0,2)*c123_2[0](2,0)+c123_1[2](1,0)*c123_2[0](0,2)-c123_1[2](1,0)*c123_2[0](2,0)-c123_1[0](1,2)*c123_2[2](0,0)+c123_1[0](1,2)*c123_2[0](2,0)+c123_1[1](2,0)*c123_2[2](0,0)-c123_1[1](2,0)*c123_2[0](0,2)+c123_1[0](2,1)*c123_2[2](0,0)-c123_1[0](2,1)*c123_2[0](0,2); row(0,113) = c123_1[2](0,1)*c123_2[0](0,1)-c123_1[2](0,1)*c123_2[0](1,0)-c123_1[1](0,2)*c123_2[1](0,0)+c123_1[1](0,2)*c123_2[0](1,0)+c123_1[2](1,0)*c123_2[0](0,1)-c123_1[2](1,0)*c123_2[0](1,0)-c123_1[0](1,2)*c123_2[1](0,0)+c123_1[0](1,2)*c123_2[0](1,0)+c123_1[1](2,0)*c123_2[1](0,0)-c123_1[1](2,0)*c123_2[0](0,1)+c123_1[0](2,1)*c123_2[1](0,0)-c123_1[0](2,1)*c123_2[0](0,1); row(0,115) = c123_1[2](0,2)*c123_2[2](0,0)-c123_1[2](0,2)*c123_2[0](0,2)-c123_1[2](2,0)*c123_2[2](0,0)+c123_1[2](2,0)*c123_2[0](2,0)+c123_1[0](2,2)*c123_2[0](0,2)-c123_1[0](2,2)*c123_2[0](2,0); row(0,116) = c123_1[2](0,2)*c123_2[1](0,0)-c123_1[2](0,2)*c123_2[0](0,1)-c123_1[2](2,0)*c123_2[1](0,0)+c123_1[2](2,0)*c123_2[0](1,0)+c123_1[0](2,2)*c123_2[0](0,1)-c123_1[0](2,2)*c123_2[0](1,0); row(0,118) = -c123_1[2](1,1)*c123_2[2](0,2)+c123_1[2](1,1)*c123_2[2](2,0)+c123_1[1](1,2)*c123_2[2](0,2)-c123_1[1](1,2)*c123_2[0](2,2)-c123_1[1](2,1)*c123_2[2](2,0)+c123_1[1](2,1)*c123_2[0](2,2); row(0,119) = -c123_1[2](1,1)*c123_2[2](0,1)+c123_1[2](1,1)*c123_2[2](1,0)+c123_1[2](1,1)*c123_2[0](1,2)-c123_1[2](1,1)*c123_2[0](2,1)+c123_1[1](1,2)*c123_2[1](0,2)-c123_1[1](1,2)*c123_2[2](1,0)-c123_1[1](1,2)*c123_2[0](1,2)+c123_1[1](1,2)*c123_2[1](2,0)+c123_1[1](2,1)*c123_2[2](0,1)-c123_1[1](2,1)*c123_2[1](0,2)-c123_1[1](2,1)*c123_2[1](2,0)+c123_1[1](2,1)*c123_2[0](2,1); row(0,120) = c123_1[2](1,1)*c123_2[0](0,2)-c123_1[2](1,1)*c123_2[0](2,0)-c123_1[1](1,2)*c123_2[2](0,0)+c123_1[1](1,2)*c123_2[0](2,0)+c123_1[1](2,1)*c123_2[2](0,0)-c123_1[1](2,1)*c123_2[0](0,2); row(0,121) = -c123_1[2](1,2)*c123_2[2](2,0)+c123_1[2](1,2)*c123_2[0](2,2)+c123_1[2](2,1)*c123_2[2](0,2)-c123_1[2](2,1)*c123_2[0](2,2)-c123_1[1](2,2)*c123_2[2](0,2)+c123_1[1](2,2)*c123_2[2](2,0); row(0,122) = c123_1[2](1,2)*c123_2[2](0,1)-c123_1[2](1,2)*c123_2[1](0,2)-c123_1[2](1,2)*c123_2[1](2,0)+c123_1[2](1,2)*c123_2[0](2,1)+c123_1[2](2,1)*c123_2[1](0,2)-c123_1[2](2,1)*c123_2[2](1,0)-c123_1[2](2,1)*c123_2[0](1,2)+c123_1[2](2,1)*c123_2[1](2,0)-c123_1[1](2,2)*c123_2[2](0,1)+c123_1[1](2,2)*c123_2[2](1,0)+c123_1[1](2,2)*c123_2[0](1,2)-c123_1[1](2,2)*c123_2[0](2,1); row(0,123) = c123_1[2](1,2)*c123_2[2](0,0)-c123_1[2](1,2)*c123_2[0](0,2)-c123_1[2](2,1)*c123_2[2](0,0)+c123_1[2](2,1)*c123_2[0](2,0)+c123_1[1](2,2)*c123_2[0](0,2)-c123_1[1](2,2)*c123_2[0](2,0); row(0,125) = -c123_1[2](1,1)*c123_2[1](0,2)-c123_1[2](1,1)*c123_2[0](1,2)+c123_1[2](1,1)*c123_2[1](2,0)+c123_1[2](1,1)*c123_2[0](2,1)+c123_1[1](1,2)*c123_2[2](0,1)+c123_1[1](1,2)*c123_2[2](1,0)-c123_1[1](1,2)*c123_2[1](2,0)-c123_1[1](1,2)*c123_2[0](2,1)-c123_1[1](2,1)*c123_2[2](0,1)+c123_1[1](2,1)*c123_2[1](0,2)-c123_1[1](2,1)*c123_2[2](1,0)+c123_1[1](2,1)*c123_2[0](1,2); row(0,126) = -c123_1[2](1,1)*c123_2[1](0,1)+c123_1[2](1,1)*c123_2[1](1,0)+c123_1[1](1,2)*c123_2[1](0,1)-c123_1[1](1,2)*c123_2[0](1,1)-c123_1[1](2,1)*c123_2[1](1,0)+c123_1[1](2,1)*c123_2[0](1,1); row(0,127) = c123_1[2](1,1)*c123_2[0](0,1)-c123_1[2](1,1)*c123_2[0](1,0)-c123_1[1](1,2)*c123_2[1](0,0)+c123_1[1](1,2)*c123_2[0](1,0)+c123_1[1](2,1)*c123_2[1](0,0)-c123_1[1](2,1)*c123_2[0](0,1); row(0,128) = -c123_1[2](1,2)*c123_2[2](0,1)+c123_1[2](1,2)*c123_2[1](0,2)-c123_1[2](1,2)*c123_2[2](1,0)+c123_1[2](1,2)*c123_2[0](1,2)+c123_1[2](2,1)*c123_2[2](0,1)+c123_1[2](2,1)*c123_2[2](1,0)-c123_1[2](2,1)*c123_2[1](2,0)-c123_1[2](2,1)*c123_2[0](2,1)-c123_1[1](2,2)*c123_2[1](0,2)-c123_1[1](2,2)*c123_2[0](1,2)+c123_1[1](2,2)*c123_2[1](2,0)+c123_1[1](2,2)*c123_2[0](2,1); row(0,129) = -c123_1[2](1,2)*c123_2[1](1,0)+c123_1[2](1,2)*c123_2[0](1,1)+c123_1[2](2,1)*c123_2[1](0,1)-c123_1[2](2,1)*c123_2[0](1,1)-c123_1[1](2,2)*c123_2[1](0,1)+c123_1[1](2,2)*c123_2[1](1,0); row(0,130) = c123_1[2](1,2)*c123_2[1](0,0)-c123_1[2](1,2)*c123_2[0](0,1)-c123_1[2](2,1)*c123_2[1](0,0)+c123_1[2](2,1)*c123_2[0](1,0)+c123_1[1](2,2)*c123_2[0](0,1)-c123_1[1](2,2)*c123_2[0](1,0); row(0,133) = -c123_1[2](1,1)*c123_2[0](0,2)+c123_1[2](1,1)*c123_2[0](2,0)+c123_1[1](1,2)*c123_2[2](0,0)-c123_1[1](1,2)*c123_2[0](2,0)-c123_1[1](2,1)*c123_2[2](0,0)+c123_1[1](2,1)*c123_2[0](0,2); row(0,134) = -c123_1[2](1,1)*c123_2[0](0,1)+c123_1[2](1,1)*c123_2[0](1,0)+c123_1[1](1,2)*c123_2[1](0,0)-c123_1[1](1,2)*c123_2[0](1,0)-c123_1[1](2,1)*c123_2[1](0,0)+c123_1[1](2,1)*c123_2[0](0,1); row(0,136) = -c123_1[2](1,2)*c123_2[2](0,0)+c123_1[2](1,2)*c123_2[0](0,2)+c123_1[2](2,1)*c123_2[2](0,0)-c123_1[2](2,1)*c123_2[0](2,0)-c123_1[1](2,2)*c123_2[0](0,2)+c123_1[1](2,2)*c123_2[0](2,0); row(0,137) = -c123_1[2](1,2)*c123_2[1](0,0)+c123_1[2](1,2)*c123_2[0](0,1)+c123_1[2](2,1)*c123_2[1](0,0)-c123_1[2](2,1)*c123_2[0](1,0)-c123_1[1](2,2)*c123_2[0](0,1)+c123_1[1](2,2)*c123_2[0](1,0); return row; }; void opengv::relative_pose::modules::fivept_kneip::initMatrix( Eigen::Matrix & groebnerMatrix) { groebnerMatrix(10,169) = 1; groebnerMatrix(10,177) = 1; groebnerMatrix(10,186) = 1; groebnerMatrix(10,196) = -1; groebnerMatrix(11,166) = 1; groebnerMatrix(11,174) = 1; groebnerMatrix(11,183) = 1; groebnerMatrix(12,163) = 1; groebnerMatrix(12,171) = 1; groebnerMatrix(12,180) = 1; groebnerMatrix(13,151) = 1; groebnerMatrix(13,156) = 1; groebnerMatrix(13,162) = 1; groebnerMatrix(13,196) = -1; groebnerMatrix(14,148) = 1; groebnerMatrix(14,153) = 1; groebnerMatrix(14,159) = 1; groebnerMatrix(15,142) = 1; groebnerMatrix(15,144) = 1; groebnerMatrix(15,147) = 1; groebnerMatrix(15,196) = -1; groebnerMatrix(16,154) = -1; groebnerMatrix(16,158) = 1; groebnerMatrix(16,193) = -1; groebnerMatrix(17,172) = 1; groebnerMatrix(17,179) = -1; groebnerMatrix(17,190) = -1; groebnerMatrix(18,175) = -1; groebnerMatrix(18,182) = 1; groebnerMatrix(18,187) = -1; groebnerMatrix(19,149) = -1; groebnerMatrix(19,152) = 1; groebnerMatrix(19,195) = -1; groebnerMatrix(20,164) = 1; groebnerMatrix(20,170) = -1; groebnerMatrix(20,192) = -1; groebnerMatrix(21,167) = -1; groebnerMatrix(21,173) = 1; groebnerMatrix(21,189) = -1; groebnerMatrix(22,147) = 1; groebnerMatrix(22,162) = 1; groebnerMatrix(22,186) = 1; groebnerMatrix(22,196) = -1; groebnerMatrix(23,146) = 1; groebnerMatrix(23,161) = 1; groebnerMatrix(23,185) = 1; groebnerMatrix(24,145) = 1; groebnerMatrix(24,160) = 1; groebnerMatrix(24,184) = 1; groebnerMatrix(25,144) = 1; groebnerMatrix(25,156) = 1; groebnerMatrix(25,177) = 1; groebnerMatrix(25,196) = -1; groebnerMatrix(26,143) = 1; groebnerMatrix(26,155) = 1; groebnerMatrix(26,176) = 1; groebnerMatrix(27,168) = 1; groebnerMatrix(27,181) = -1; groebnerMatrix(27,188) = -1; groebnerMatrix(28,150) = 1; groebnerMatrix(28,157) = -1; groebnerMatrix(28,194) = -1; groebnerMatrix(29,165) = -1; groebnerMatrix(29,178) = 1; groebnerMatrix(29,191) = -1; } opengv/src/relative_pose/modules/fivept_kneip/code.cpp0000664016516101651610000176461113344612246022230 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::relative_pose::modules::fivept_kneip::computeBasis( Eigen::Matrix & groebnerMatrix ) { double factor = 0.0; sPolynomial30(groebnerMatrix); factor = -groebnerMatrix(30,1); groebnerMatrix(30,1) = 0.0; groebnerMatrix(30,8) = groebnerMatrix(30,8) - factor * groebnerMatrix(19,152); groebnerMatrix(30,179) = groebnerMatrix(30,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(30,2); groebnerMatrix(30,2) = 0.0; groebnerMatrix(30,11) = groebnerMatrix(30,11) - factor * groebnerMatrix(14,153); groebnerMatrix(30,24) = groebnerMatrix(30,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(30,3); groebnerMatrix(30,3) = 0.0; groebnerMatrix(30,10) = groebnerMatrix(30,10) - factor * groebnerMatrix(19,152); groebnerMatrix(30,180) = groebnerMatrix(30,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(30,4); groebnerMatrix(30,4) = 0.0; groebnerMatrix(30,36) = groebnerMatrix(30,36) - factor * groebnerMatrix(22,162); groebnerMatrix(30,136) = groebnerMatrix(30,136) - factor * groebnerMatrix(22,186); groebnerMatrix(30,190) = groebnerMatrix(30,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(30,5); groebnerMatrix(30,5) = 0.0; groebnerMatrix(30,17) = groebnerMatrix(30,17) - factor * groebnerMatrix(13,156); groebnerMatrix(30,34) = groebnerMatrix(30,34) - factor * groebnerMatrix(13,162); groebnerMatrix(30,188) = groebnerMatrix(30,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(30,6); groebnerMatrix(30,6) = 0.0; groebnerMatrix(30,18) = groebnerMatrix(30,18) - factor * groebnerMatrix(13,156); groebnerMatrix(30,35) = groebnerMatrix(30,35) - factor * groebnerMatrix(13,162); groebnerMatrix(30,189) = groebnerMatrix(30,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(30,10); groebnerMatrix(30,10) = 0.0; groebnerMatrix(30,20) = groebnerMatrix(30,20) - factor * groebnerMatrix(16,158); groebnerMatrix(30,163) = groebnerMatrix(30,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(30,11); groebnerMatrix(30,11) = 0.0; groebnerMatrix(30,21) = groebnerMatrix(30,21) - factor * groebnerMatrix(16,158); groebnerMatrix(30,164) = groebnerMatrix(30,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(30,12); groebnerMatrix(30,12) = 0.0; groebnerMatrix(30,23) = groebnerMatrix(30,23) - factor * groebnerMatrix(16,158); groebnerMatrix(30,165) = groebnerMatrix(30,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(30,13); groebnerMatrix(30,13) = 0.0; groebnerMatrix(30,17) = groebnerMatrix(30,17) - factor * groebnerMatrix(14,153); groebnerMatrix(30,30) = groebnerMatrix(30,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(30,14); groebnerMatrix(30,14) = 0.0; groebnerMatrix(30,16) = groebnerMatrix(30,16) - factor * groebnerMatrix(19,152); groebnerMatrix(30,182) = groebnerMatrix(30,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(30,15); groebnerMatrix(30,15) = 0.0; groebnerMatrix(30,26) = groebnerMatrix(30,26) - factor * groebnerMatrix(16,158); groebnerMatrix(30,166) = groebnerMatrix(30,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(30,18); groebnerMatrix(30,18) = 0.0; groebnerMatrix(30,29) = groebnerMatrix(30,29) - factor * groebnerMatrix(16,158); groebnerMatrix(30,167) = groebnerMatrix(30,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(30,19); groebnerMatrix(30,19) = 0.0; groebnerMatrix(30,21) = groebnerMatrix(30,21) - factor * groebnerMatrix(15,144); groebnerMatrix(30,24) = groebnerMatrix(30,24) - factor * groebnerMatrix(15,147); groebnerMatrix(30,192) = groebnerMatrix(30,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(30,22); groebnerMatrix(30,22) = 0.0; groebnerMatrix(30,36) = groebnerMatrix(30,36) - factor * groebnerMatrix(24,160); groebnerMatrix(30,123) = groebnerMatrix(30,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(30,25); groebnerMatrix(30,25) = 0.0; groebnerMatrix(30,29) = groebnerMatrix(30,29) - factor * groebnerMatrix(14,153); groebnerMatrix(30,35) = groebnerMatrix(30,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(30,26); groebnerMatrix(30,26) = 0.0; groebnerMatrix(30,28) = groebnerMatrix(30,28) - factor * groebnerMatrix(19,152); groebnerMatrix(30,183) = groebnerMatrix(30,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(30,27); groebnerMatrix(30,27) = 0.0; groebnerMatrix(30,33) = groebnerMatrix(30,33) - factor * groebnerMatrix(28,157); groebnerMatrix(30,175) = groebnerMatrix(30,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(30,30); groebnerMatrix(30,30) = 0.0; groebnerMatrix(30,34) = groebnerMatrix(30,34) - factor * groebnerMatrix(16,158); groebnerMatrix(30,168) = groebnerMatrix(30,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(30,39); groebnerMatrix(30,39) = 0.0; groebnerMatrix(30,63) = groebnerMatrix(30,63) - factor * groebnerMatrix(12,171); groebnerMatrix(30,101) = groebnerMatrix(30,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,40); groebnerMatrix(30,40) = 0.0; groebnerMatrix(30,62) = groebnerMatrix(30,62) - factor * groebnerMatrix(20,170); groebnerMatrix(30,158) = groebnerMatrix(30,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(30,41); groebnerMatrix(30,41) = 0.0; groebnerMatrix(30,65) = groebnerMatrix(30,65) - factor * groebnerMatrix(12,171); groebnerMatrix(30,102) = groebnerMatrix(30,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,42); groebnerMatrix(30,42) = 0.0; groebnerMatrix(30,64) = groebnerMatrix(30,64) - factor * groebnerMatrix(20,170); groebnerMatrix(30,159) = groebnerMatrix(30,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(30,43); groebnerMatrix(30,43) = 0.0; groebnerMatrix(30,56) = groebnerMatrix(30,56) - factor * groebnerMatrix(22,162); groebnerMatrix(30,139) = groebnerMatrix(30,139) - factor * groebnerMatrix(22,186); groebnerMatrix(30,193) = groebnerMatrix(30,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(30,44); groebnerMatrix(30,44) = 0.0; groebnerMatrix(30,72) = groebnerMatrix(30,72) - factor * groebnerMatrix(11,174); groebnerMatrix(30,113) = groebnerMatrix(30,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(30,45); groebnerMatrix(30,45) = 0.0; groebnerMatrix(30,73) = groebnerMatrix(30,73) - factor * groebnerMatrix(11,174); groebnerMatrix(30,114) = groebnerMatrix(30,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(30,46); groebnerMatrix(30,46) = 0.0; groebnerMatrix(30,72) = groebnerMatrix(30,72) - factor * groebnerMatrix(12,171); groebnerMatrix(30,109) = groebnerMatrix(30,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,47); groebnerMatrix(30,47) = 0.0; groebnerMatrix(30,71) = groebnerMatrix(30,71) - factor * groebnerMatrix(20,170); groebnerMatrix(30,161) = groebnerMatrix(30,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(30,48); groebnerMatrix(30,48) = 0.0; groebnerMatrix(30,52) = groebnerMatrix(30,52) - factor * groebnerMatrix(16,158); groebnerMatrix(30,169) = groebnerMatrix(30,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(30,49); groebnerMatrix(30,49) = 0.0; groebnerMatrix(30,75) = groebnerMatrix(30,75) - factor * groebnerMatrix(11,174); groebnerMatrix(30,116) = groebnerMatrix(30,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(30,50); groebnerMatrix(30,50) = 0.0; groebnerMatrix(30,74) = groebnerMatrix(30,74) - factor * groebnerMatrix(21,173); groebnerMatrix(30,154) = groebnerMatrix(30,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(30,51); groebnerMatrix(30,51) = 0.0; groebnerMatrix(30,77) = groebnerMatrix(30,77) - factor * groebnerMatrix(12,171); groebnerMatrix(30,114) = groebnerMatrix(30,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,52); groebnerMatrix(30,52) = 0.0; groebnerMatrix(30,76) = groebnerMatrix(30,76) - factor * groebnerMatrix(20,170); groebnerMatrix(30,162) = groebnerMatrix(30,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(30,53); groebnerMatrix(30,53) = 0.0; groebnerMatrix(30,105) = groebnerMatrix(30,105) - factor * groebnerMatrix(27,181); groebnerMatrix(30,146) = groebnerMatrix(30,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(30,54); groebnerMatrix(30,54) = 0.0; groebnerMatrix(30,80) = groebnerMatrix(30,80) - factor * groebnerMatrix(11,174); groebnerMatrix(30,117) = groebnerMatrix(30,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(30,55); groebnerMatrix(30,55) = 0.0; groebnerMatrix(30,79) = groebnerMatrix(30,79) - factor * groebnerMatrix(21,173); groebnerMatrix(30,159) = groebnerMatrix(30,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(30,56); groebnerMatrix(30,56) = 0.0; groebnerMatrix(30,115) = groebnerMatrix(30,115) - factor * groebnerMatrix(27,181); groebnerMatrix(30,158) = groebnerMatrix(30,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(30,57); groebnerMatrix(30,57) = 0.0; groebnerMatrix(30,90) = groebnerMatrix(30,90) - factor * groebnerMatrix(10,177); groebnerMatrix(30,134) = groebnerMatrix(30,134) - factor * groebnerMatrix(10,186); groebnerMatrix(30,188) = groebnerMatrix(30,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(30,58); groebnerMatrix(30,58) = 0.0; groebnerMatrix(30,91) = groebnerMatrix(30,91) - factor * groebnerMatrix(10,177); groebnerMatrix(30,135) = groebnerMatrix(30,135) - factor * groebnerMatrix(10,186); groebnerMatrix(30,189) = groebnerMatrix(30,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(30,59); groebnerMatrix(30,59) = 0.0; groebnerMatrix(30,93) = groebnerMatrix(30,93) - factor * groebnerMatrix(10,177); groebnerMatrix(30,137) = groebnerMatrix(30,137) - factor * groebnerMatrix(10,186); groebnerMatrix(30,191) = groebnerMatrix(30,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(30,60); groebnerMatrix(30,60) = 0.0; groebnerMatrix(30,94) = groebnerMatrix(30,94) - factor * groebnerMatrix(10,177); groebnerMatrix(30,138) = groebnerMatrix(30,138) - factor * groebnerMatrix(10,186); groebnerMatrix(30,192) = groebnerMatrix(30,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(30,61); groebnerMatrix(30,61) = 0.0; groebnerMatrix(30,63) = groebnerMatrix(30,63) - factor * groebnerMatrix(15,144); groebnerMatrix(30,66) = groebnerMatrix(30,66) - factor * groebnerMatrix(15,147); groebnerMatrix(30,194) = groebnerMatrix(30,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(30,64); groebnerMatrix(30,64) = 0.0; groebnerMatrix(30,98) = groebnerMatrix(30,98) - factor * groebnerMatrix(17,179); groebnerMatrix(30,148) = groebnerMatrix(30,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(30,65); groebnerMatrix(30,65) = 0.0; groebnerMatrix(30,99) = groebnerMatrix(30,99) - factor * groebnerMatrix(17,179); groebnerMatrix(30,149) = groebnerMatrix(30,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(30,66); groebnerMatrix(30,66) = 0.0; groebnerMatrix(30,101) = groebnerMatrix(30,101) - factor * groebnerMatrix(17,179); groebnerMatrix(30,150) = groebnerMatrix(30,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(30,67); groebnerMatrix(30,67) = 0.0; groebnerMatrix(30,72) = groebnerMatrix(30,72) - factor * groebnerMatrix(14,153); groebnerMatrix(30,78) = groebnerMatrix(30,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(30,68); groebnerMatrix(30,68) = 0.0; groebnerMatrix(30,71) = groebnerMatrix(30,71) - factor * groebnerMatrix(19,152); groebnerMatrix(30,185) = groebnerMatrix(30,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(30,69); groebnerMatrix(30,69) = 0.0; groebnerMatrix(30,104) = groebnerMatrix(30,104) - factor * groebnerMatrix(17,179); groebnerMatrix(30,151) = groebnerMatrix(30,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(30,70); groebnerMatrix(30,70) = 0.0; groebnerMatrix(30,75) = groebnerMatrix(30,75) - factor * groebnerMatrix(13,156); groebnerMatrix(30,81) = groebnerMatrix(30,81) - factor * groebnerMatrix(13,162); groebnerMatrix(30,194) = groebnerMatrix(30,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(30,73); groebnerMatrix(30,73) = 0.0; groebnerMatrix(30,77) = groebnerMatrix(30,77) - factor * groebnerMatrix(16,158); groebnerMatrix(30,176) = groebnerMatrix(30,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(30,76); groebnerMatrix(30,76) = 0.0; groebnerMatrix(30,107) = groebnerMatrix(30,107) - factor * groebnerMatrix(18,182); groebnerMatrix(30,142) = groebnerMatrix(30,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(30,77); groebnerMatrix(30,77) = 0.0; groebnerMatrix(30,108) = groebnerMatrix(30,108) - factor * groebnerMatrix(18,182); groebnerMatrix(30,143) = groebnerMatrix(30,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(30,78); groebnerMatrix(30,78) = 0.0; groebnerMatrix(30,113) = groebnerMatrix(30,113) - factor * groebnerMatrix(17,179); groebnerMatrix(30,160) = groebnerMatrix(30,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(30,79); groebnerMatrix(30,79) = 0.0; groebnerMatrix(30,110) = groebnerMatrix(30,110) - factor * groebnerMatrix(18,182); groebnerMatrix(30,148) = groebnerMatrix(30,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(30,80); groebnerMatrix(30,80) = 0.0; groebnerMatrix(30,111) = groebnerMatrix(30,111) - factor * groebnerMatrix(18,182); groebnerMatrix(30,152) = groebnerMatrix(30,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(30,81); groebnerMatrix(30,81) = 0.0; groebnerMatrix(30,116) = groebnerMatrix(30,116) - factor * groebnerMatrix(18,182); groebnerMatrix(30,157) = groebnerMatrix(30,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(30,82); groebnerMatrix(30,82) = 0.0; groebnerMatrix(30,90) = groebnerMatrix(30,90) - factor * groebnerMatrix(12,171); groebnerMatrix(30,127) = groebnerMatrix(30,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,83); groebnerMatrix(30,83) = 0.0; groebnerMatrix(30,89) = groebnerMatrix(30,89) - factor * groebnerMatrix(20,170); groebnerMatrix(30,175) = groebnerMatrix(30,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(30,84); groebnerMatrix(30,84) = 0.0; groebnerMatrix(30,119) = groebnerMatrix(30,119) - factor * groebnerMatrix(17,179); groebnerMatrix(30,166) = groebnerMatrix(30,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(30,85); groebnerMatrix(30,85) = 0.0; groebnerMatrix(30,93) = groebnerMatrix(30,93) - factor * groebnerMatrix(11,174); groebnerMatrix(30,130) = groebnerMatrix(30,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(30,86); groebnerMatrix(30,86) = 0.0; groebnerMatrix(30,92) = groebnerMatrix(30,92) - factor * groebnerMatrix(21,173); groebnerMatrix(30,172) = groebnerMatrix(30,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(30,87); groebnerMatrix(30,87) = 0.0; groebnerMatrix(30,122) = groebnerMatrix(30,122) - factor * groebnerMatrix(18,182); groebnerMatrix(30,163) = groebnerMatrix(30,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(30,91); groebnerMatrix(30,91) = 0.0; groebnerMatrix(30,126) = groebnerMatrix(30,126) - factor * groebnerMatrix(17,179); groebnerMatrix(30,173) = groebnerMatrix(30,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(30,94); groebnerMatrix(30,94) = 0.0; groebnerMatrix(30,129) = groebnerMatrix(30,129) - factor * groebnerMatrix(18,182); groebnerMatrix(30,170) = groebnerMatrix(30,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(30,97); groebnerMatrix(30,97) = 0.0; groebnerMatrix(30,99) = groebnerMatrix(30,99) - factor * groebnerMatrix(15,144); groebnerMatrix(30,102) = groebnerMatrix(30,102) - factor * groebnerMatrix(15,147); groebnerMatrix(30,195) = groebnerMatrix(30,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(30,100); groebnerMatrix(30,100) = 0.0; groebnerMatrix(30,115) = groebnerMatrix(30,115) - factor * groebnerMatrix(24,160); groebnerMatrix(30,139) = groebnerMatrix(30,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(30,103); groebnerMatrix(30,103) = 0.0; groebnerMatrix(30,108) = groebnerMatrix(30,108) - factor * groebnerMatrix(14,153); groebnerMatrix(30,114) = groebnerMatrix(30,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(30,104); groebnerMatrix(30,104) = 0.0; groebnerMatrix(30,107) = groebnerMatrix(30,107) - factor * groebnerMatrix(19,152); groebnerMatrix(30,186) = groebnerMatrix(30,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(30,105); groebnerMatrix(30,105) = 0.0; groebnerMatrix(30,112) = groebnerMatrix(30,112) - factor * groebnerMatrix(28,157); groebnerMatrix(30,185) = groebnerMatrix(30,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(30,106); groebnerMatrix(30,106) = 0.0; groebnerMatrix(30,111) = groebnerMatrix(30,111) - factor * groebnerMatrix(13,156); groebnerMatrix(30,117) = groebnerMatrix(30,117) - factor * groebnerMatrix(13,162); groebnerMatrix(30,195) = groebnerMatrix(30,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(30,109); groebnerMatrix(30,109) = 0.0; groebnerMatrix(30,113) = groebnerMatrix(30,113) - factor * groebnerMatrix(16,158); groebnerMatrix(30,184) = groebnerMatrix(30,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(30,118); groebnerMatrix(30,118) = 0.0; groebnerMatrix(30,126) = groebnerMatrix(30,126) - factor * groebnerMatrix(12,171); groebnerMatrix(30,135) = groebnerMatrix(30,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,119); groebnerMatrix(30,119) = 0.0; groebnerMatrix(30,125) = groebnerMatrix(30,125) - factor * groebnerMatrix(20,170); groebnerMatrix(30,183) = groebnerMatrix(30,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(30,120); groebnerMatrix(30,120) = 0.0; groebnerMatrix(30,133) = groebnerMatrix(30,133) - factor * groebnerMatrix(29,178); groebnerMatrix(30,182) = groebnerMatrix(30,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(30,121); groebnerMatrix(30,121) = 0.0; groebnerMatrix(30,129) = groebnerMatrix(30,129) - factor * groebnerMatrix(11,174); groebnerMatrix(30,138) = groebnerMatrix(30,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(30,122); groebnerMatrix(30,122) = 0.0; groebnerMatrix(30,128) = groebnerMatrix(30,128) - factor * groebnerMatrix(21,173); groebnerMatrix(30,180) = groebnerMatrix(30,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(30,123); groebnerMatrix(30,123) = 0.0; groebnerMatrix(30,136) = groebnerMatrix(30,136) - factor * groebnerMatrix(27,181); groebnerMatrix(30,179) = groebnerMatrix(30,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(30,127); groebnerMatrix(30,127) = 0.0; groebnerMatrix(30,134) = groebnerMatrix(30,134) - factor * groebnerMatrix(17,179); groebnerMatrix(30,181) = groebnerMatrix(30,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(30,130); groebnerMatrix(30,130) = 0.0; groebnerMatrix(30,137) = groebnerMatrix(30,137) - factor * groebnerMatrix(18,182); groebnerMatrix(30,178) = groebnerMatrix(30,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(30,142); groebnerMatrix(30,142) = 0.0; groebnerMatrix(30,144) = groebnerMatrix(30,144) - factor * groebnerMatrix(15,144); groebnerMatrix(30,147) = groebnerMatrix(30,147) - factor * groebnerMatrix(15,147); groebnerMatrix(30,196) = groebnerMatrix(30,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(30,143); groebnerMatrix(30,143) = 0.0; groebnerMatrix(30,155) = groebnerMatrix(30,155) - factor * groebnerMatrix(26,155); groebnerMatrix(30,176) = groebnerMatrix(30,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(30,144); groebnerMatrix(30,144) = 0.0; groebnerMatrix(30,156) = groebnerMatrix(30,156) - factor * groebnerMatrix(25,156); groebnerMatrix(30,177) = groebnerMatrix(30,177) - factor * groebnerMatrix(25,177); groebnerMatrix(30,196) = groebnerMatrix(30,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(30,146); groebnerMatrix(30,146) = 0.0; groebnerMatrix(30,161) = groebnerMatrix(30,161) - factor * groebnerMatrix(23,161); groebnerMatrix(30,185) = groebnerMatrix(30,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(30,147); groebnerMatrix(30,147) = 0.0; groebnerMatrix(30,162) = groebnerMatrix(30,162) - factor * groebnerMatrix(22,162); groebnerMatrix(30,186) = groebnerMatrix(30,186) - factor * groebnerMatrix(22,186); groebnerMatrix(30,196) = groebnerMatrix(30,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(30,148); groebnerMatrix(30,148) = 0.0; groebnerMatrix(30,153) = groebnerMatrix(30,153) - factor * groebnerMatrix(14,153); groebnerMatrix(30,159) = groebnerMatrix(30,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(30,149); groebnerMatrix(30,149) = 0.0; groebnerMatrix(30,152) = groebnerMatrix(30,152) - factor * groebnerMatrix(19,152); groebnerMatrix(30,195) = groebnerMatrix(30,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(30,150); groebnerMatrix(30,150) = 0.0; groebnerMatrix(30,157) = groebnerMatrix(30,157) - factor * groebnerMatrix(28,157); groebnerMatrix(30,194) = groebnerMatrix(30,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(30,151); groebnerMatrix(30,151) = 0.0; groebnerMatrix(30,156) = groebnerMatrix(30,156) - factor * groebnerMatrix(13,156); groebnerMatrix(30,162) = groebnerMatrix(30,162) - factor * groebnerMatrix(13,162); groebnerMatrix(30,196) = groebnerMatrix(30,196) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(30,154); groebnerMatrix(30,154) = 0.0; groebnerMatrix(30,158) = groebnerMatrix(30,158) - factor * groebnerMatrix(16,158); groebnerMatrix(30,193) = groebnerMatrix(30,193) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(30,163); groebnerMatrix(30,163) = 0.0; groebnerMatrix(30,171) = groebnerMatrix(30,171) - factor * groebnerMatrix(12,171); groebnerMatrix(30,180) = groebnerMatrix(30,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(30,164); groebnerMatrix(30,164) = 0.0; groebnerMatrix(30,170) = groebnerMatrix(30,170) - factor * groebnerMatrix(20,170); groebnerMatrix(30,192) = groebnerMatrix(30,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(30,165); groebnerMatrix(30,165) = 0.0; groebnerMatrix(30,178) = groebnerMatrix(30,178) - factor * groebnerMatrix(29,178); groebnerMatrix(30,191) = groebnerMatrix(30,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(30,166); groebnerMatrix(30,166) = 0.0; groebnerMatrix(30,174) = groebnerMatrix(30,174) - factor * groebnerMatrix(11,174); groebnerMatrix(30,183) = groebnerMatrix(30,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(30,167); groebnerMatrix(30,167) = 0.0; groebnerMatrix(30,173) = groebnerMatrix(30,173) - factor * groebnerMatrix(21,173); groebnerMatrix(30,189) = groebnerMatrix(30,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(30,168); groebnerMatrix(30,168) = 0.0; groebnerMatrix(30,181) = groebnerMatrix(30,181) - factor * groebnerMatrix(27,181); groebnerMatrix(30,188) = groebnerMatrix(30,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(30,169); groebnerMatrix(30,169) = 0.0; groebnerMatrix(30,177) = groebnerMatrix(30,177) - factor * groebnerMatrix(10,177); groebnerMatrix(30,186) = groebnerMatrix(30,186) - factor * groebnerMatrix(10,186); groebnerMatrix(30,196) = groebnerMatrix(30,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(30,172); groebnerMatrix(30,172) = 0.0; groebnerMatrix(30,179) = groebnerMatrix(30,179) - factor * groebnerMatrix(17,179); groebnerMatrix(30,190) = groebnerMatrix(30,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(30,175); groebnerMatrix(30,175) = 0.0; groebnerMatrix(30,182) = groebnerMatrix(30,182) - factor * groebnerMatrix(18,182); groebnerMatrix(30,187) = groebnerMatrix(30,187) - factor * groebnerMatrix(18,187); sPolynomial31(groebnerMatrix); factor = -groebnerMatrix(31,1); groebnerMatrix(31,1) = 0.0; groebnerMatrix(31,8) = groebnerMatrix(31,8) - factor * groebnerMatrix(19,152); groebnerMatrix(31,179) = groebnerMatrix(31,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(31,2); groebnerMatrix(31,2) = 0.0; groebnerMatrix(31,11) = groebnerMatrix(31,11) - factor * groebnerMatrix(14,153); groebnerMatrix(31,24) = groebnerMatrix(31,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(31,3); groebnerMatrix(31,3) = 0.0; groebnerMatrix(31,10) = groebnerMatrix(31,10) - factor * groebnerMatrix(19,152); groebnerMatrix(31,180) = groebnerMatrix(31,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(31,4); groebnerMatrix(31,4) = 0.0; groebnerMatrix(31,36) = groebnerMatrix(31,36) - factor * groebnerMatrix(22,162); groebnerMatrix(31,136) = groebnerMatrix(31,136) - factor * groebnerMatrix(22,186); groebnerMatrix(31,190) = groebnerMatrix(31,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(31,5); groebnerMatrix(31,5) = 0.0; groebnerMatrix(31,17) = groebnerMatrix(31,17) - factor * groebnerMatrix(13,156); groebnerMatrix(31,34) = groebnerMatrix(31,34) - factor * groebnerMatrix(13,162); groebnerMatrix(31,188) = groebnerMatrix(31,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(31,6); groebnerMatrix(31,6) = 0.0; groebnerMatrix(31,18) = groebnerMatrix(31,18) - factor * groebnerMatrix(13,156); groebnerMatrix(31,35) = groebnerMatrix(31,35) - factor * groebnerMatrix(13,162); groebnerMatrix(31,189) = groebnerMatrix(31,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(31,10); groebnerMatrix(31,10) = 0.0; groebnerMatrix(31,20) = groebnerMatrix(31,20) - factor * groebnerMatrix(16,158); groebnerMatrix(31,163) = groebnerMatrix(31,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(31,11); groebnerMatrix(31,11) = 0.0; groebnerMatrix(31,21) = groebnerMatrix(31,21) - factor * groebnerMatrix(16,158); groebnerMatrix(31,164) = groebnerMatrix(31,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(31,12); groebnerMatrix(31,12) = 0.0; groebnerMatrix(31,23) = groebnerMatrix(31,23) - factor * groebnerMatrix(16,158); groebnerMatrix(31,165) = groebnerMatrix(31,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(31,13); groebnerMatrix(31,13) = 0.0; groebnerMatrix(31,17) = groebnerMatrix(31,17) - factor * groebnerMatrix(14,153); groebnerMatrix(31,30) = groebnerMatrix(31,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(31,14); groebnerMatrix(31,14) = 0.0; groebnerMatrix(31,16) = groebnerMatrix(31,16) - factor * groebnerMatrix(19,152); groebnerMatrix(31,182) = groebnerMatrix(31,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(31,15); groebnerMatrix(31,15) = 0.0; groebnerMatrix(31,26) = groebnerMatrix(31,26) - factor * groebnerMatrix(16,158); groebnerMatrix(31,166) = groebnerMatrix(31,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(31,18); groebnerMatrix(31,18) = 0.0; groebnerMatrix(31,29) = groebnerMatrix(31,29) - factor * groebnerMatrix(16,158); groebnerMatrix(31,167) = groebnerMatrix(31,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(31,19); groebnerMatrix(31,19) = 0.0; groebnerMatrix(31,21) = groebnerMatrix(31,21) - factor * groebnerMatrix(15,144); groebnerMatrix(31,24) = groebnerMatrix(31,24) - factor * groebnerMatrix(15,147); groebnerMatrix(31,192) = groebnerMatrix(31,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(31,22); groebnerMatrix(31,22) = 0.0; groebnerMatrix(31,36) = groebnerMatrix(31,36) - factor * groebnerMatrix(24,160); groebnerMatrix(31,123) = groebnerMatrix(31,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(31,25); groebnerMatrix(31,25) = 0.0; groebnerMatrix(31,29) = groebnerMatrix(31,29) - factor * groebnerMatrix(14,153); groebnerMatrix(31,35) = groebnerMatrix(31,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(31,26); groebnerMatrix(31,26) = 0.0; groebnerMatrix(31,28) = groebnerMatrix(31,28) - factor * groebnerMatrix(19,152); groebnerMatrix(31,183) = groebnerMatrix(31,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(31,27); groebnerMatrix(31,27) = 0.0; groebnerMatrix(31,33) = groebnerMatrix(31,33) - factor * groebnerMatrix(28,157); groebnerMatrix(31,175) = groebnerMatrix(31,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(31,30); groebnerMatrix(31,30) = 0.0; groebnerMatrix(31,34) = groebnerMatrix(31,34) - factor * groebnerMatrix(16,158); groebnerMatrix(31,168) = groebnerMatrix(31,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(31,39); groebnerMatrix(31,39) = 0.0; groebnerMatrix(31,63) = groebnerMatrix(31,63) - factor * groebnerMatrix(12,171); groebnerMatrix(31,101) = groebnerMatrix(31,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,40); groebnerMatrix(31,40) = 0.0; groebnerMatrix(31,62) = groebnerMatrix(31,62) - factor * groebnerMatrix(20,170); groebnerMatrix(31,158) = groebnerMatrix(31,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(31,41); groebnerMatrix(31,41) = 0.0; groebnerMatrix(31,65) = groebnerMatrix(31,65) - factor * groebnerMatrix(12,171); groebnerMatrix(31,102) = groebnerMatrix(31,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,42); groebnerMatrix(31,42) = 0.0; groebnerMatrix(31,64) = groebnerMatrix(31,64) - factor * groebnerMatrix(20,170); groebnerMatrix(31,159) = groebnerMatrix(31,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(31,43); groebnerMatrix(31,43) = 0.0; groebnerMatrix(31,56) = groebnerMatrix(31,56) - factor * groebnerMatrix(22,162); groebnerMatrix(31,139) = groebnerMatrix(31,139) - factor * groebnerMatrix(22,186); groebnerMatrix(31,193) = groebnerMatrix(31,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(31,44); groebnerMatrix(31,44) = 0.0; groebnerMatrix(31,72) = groebnerMatrix(31,72) - factor * groebnerMatrix(11,174); groebnerMatrix(31,113) = groebnerMatrix(31,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(31,45); groebnerMatrix(31,45) = 0.0; groebnerMatrix(31,73) = groebnerMatrix(31,73) - factor * groebnerMatrix(11,174); groebnerMatrix(31,114) = groebnerMatrix(31,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(31,46); groebnerMatrix(31,46) = 0.0; groebnerMatrix(31,72) = groebnerMatrix(31,72) - factor * groebnerMatrix(12,171); groebnerMatrix(31,109) = groebnerMatrix(31,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,47); groebnerMatrix(31,47) = 0.0; groebnerMatrix(31,71) = groebnerMatrix(31,71) - factor * groebnerMatrix(20,170); groebnerMatrix(31,161) = groebnerMatrix(31,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(31,48); groebnerMatrix(31,48) = 0.0; groebnerMatrix(31,52) = groebnerMatrix(31,52) - factor * groebnerMatrix(16,158); groebnerMatrix(31,169) = groebnerMatrix(31,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(31,49); groebnerMatrix(31,49) = 0.0; groebnerMatrix(31,75) = groebnerMatrix(31,75) - factor * groebnerMatrix(11,174); groebnerMatrix(31,116) = groebnerMatrix(31,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(31,50); groebnerMatrix(31,50) = 0.0; groebnerMatrix(31,74) = groebnerMatrix(31,74) - factor * groebnerMatrix(21,173); groebnerMatrix(31,154) = groebnerMatrix(31,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(31,51); groebnerMatrix(31,51) = 0.0; groebnerMatrix(31,77) = groebnerMatrix(31,77) - factor * groebnerMatrix(12,171); groebnerMatrix(31,114) = groebnerMatrix(31,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,52); groebnerMatrix(31,52) = 0.0; groebnerMatrix(31,76) = groebnerMatrix(31,76) - factor * groebnerMatrix(20,170); groebnerMatrix(31,162) = groebnerMatrix(31,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(31,53); groebnerMatrix(31,53) = 0.0; groebnerMatrix(31,105) = groebnerMatrix(31,105) - factor * groebnerMatrix(27,181); groebnerMatrix(31,146) = groebnerMatrix(31,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(31,54); groebnerMatrix(31,54) = 0.0; groebnerMatrix(31,80) = groebnerMatrix(31,80) - factor * groebnerMatrix(11,174); groebnerMatrix(31,117) = groebnerMatrix(31,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(31,55); groebnerMatrix(31,55) = 0.0; groebnerMatrix(31,79) = groebnerMatrix(31,79) - factor * groebnerMatrix(21,173); groebnerMatrix(31,159) = groebnerMatrix(31,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(31,56); groebnerMatrix(31,56) = 0.0; groebnerMatrix(31,115) = groebnerMatrix(31,115) - factor * groebnerMatrix(27,181); groebnerMatrix(31,158) = groebnerMatrix(31,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(31,57); groebnerMatrix(31,57) = 0.0; groebnerMatrix(31,90) = groebnerMatrix(31,90) - factor * groebnerMatrix(10,177); groebnerMatrix(31,134) = groebnerMatrix(31,134) - factor * groebnerMatrix(10,186); groebnerMatrix(31,188) = groebnerMatrix(31,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(31,58); groebnerMatrix(31,58) = 0.0; groebnerMatrix(31,91) = groebnerMatrix(31,91) - factor * groebnerMatrix(10,177); groebnerMatrix(31,135) = groebnerMatrix(31,135) - factor * groebnerMatrix(10,186); groebnerMatrix(31,189) = groebnerMatrix(31,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(31,59); groebnerMatrix(31,59) = 0.0; groebnerMatrix(31,93) = groebnerMatrix(31,93) - factor * groebnerMatrix(10,177); groebnerMatrix(31,137) = groebnerMatrix(31,137) - factor * groebnerMatrix(10,186); groebnerMatrix(31,191) = groebnerMatrix(31,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(31,60); groebnerMatrix(31,60) = 0.0; groebnerMatrix(31,94) = groebnerMatrix(31,94) - factor * groebnerMatrix(10,177); groebnerMatrix(31,138) = groebnerMatrix(31,138) - factor * groebnerMatrix(10,186); groebnerMatrix(31,192) = groebnerMatrix(31,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(31,61); groebnerMatrix(31,61) = 0.0; groebnerMatrix(31,63) = groebnerMatrix(31,63) - factor * groebnerMatrix(15,144); groebnerMatrix(31,66) = groebnerMatrix(31,66) - factor * groebnerMatrix(15,147); groebnerMatrix(31,194) = groebnerMatrix(31,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(31,64); groebnerMatrix(31,64) = 0.0; groebnerMatrix(31,98) = groebnerMatrix(31,98) - factor * groebnerMatrix(17,179); groebnerMatrix(31,148) = groebnerMatrix(31,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(31,65); groebnerMatrix(31,65) = 0.0; groebnerMatrix(31,99) = groebnerMatrix(31,99) - factor * groebnerMatrix(17,179); groebnerMatrix(31,149) = groebnerMatrix(31,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(31,66); groebnerMatrix(31,66) = 0.0; groebnerMatrix(31,101) = groebnerMatrix(31,101) - factor * groebnerMatrix(17,179); groebnerMatrix(31,150) = groebnerMatrix(31,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(31,67); groebnerMatrix(31,67) = 0.0; groebnerMatrix(31,72) = groebnerMatrix(31,72) - factor * groebnerMatrix(14,153); groebnerMatrix(31,78) = groebnerMatrix(31,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(31,68); groebnerMatrix(31,68) = 0.0; groebnerMatrix(31,71) = groebnerMatrix(31,71) - factor * groebnerMatrix(19,152); groebnerMatrix(31,185) = groebnerMatrix(31,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(31,69); groebnerMatrix(31,69) = 0.0; groebnerMatrix(31,104) = groebnerMatrix(31,104) - factor * groebnerMatrix(17,179); groebnerMatrix(31,151) = groebnerMatrix(31,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(31,70); groebnerMatrix(31,70) = 0.0; groebnerMatrix(31,75) = groebnerMatrix(31,75) - factor * groebnerMatrix(13,156); groebnerMatrix(31,81) = groebnerMatrix(31,81) - factor * groebnerMatrix(13,162); groebnerMatrix(31,194) = groebnerMatrix(31,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(31,73); groebnerMatrix(31,73) = 0.0; groebnerMatrix(31,77) = groebnerMatrix(31,77) - factor * groebnerMatrix(16,158); groebnerMatrix(31,176) = groebnerMatrix(31,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(31,76); groebnerMatrix(31,76) = 0.0; groebnerMatrix(31,107) = groebnerMatrix(31,107) - factor * groebnerMatrix(18,182); groebnerMatrix(31,142) = groebnerMatrix(31,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(31,77); groebnerMatrix(31,77) = 0.0; groebnerMatrix(31,108) = groebnerMatrix(31,108) - factor * groebnerMatrix(18,182); groebnerMatrix(31,143) = groebnerMatrix(31,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(31,78); groebnerMatrix(31,78) = 0.0; groebnerMatrix(31,113) = groebnerMatrix(31,113) - factor * groebnerMatrix(17,179); groebnerMatrix(31,160) = groebnerMatrix(31,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(31,79); groebnerMatrix(31,79) = 0.0; groebnerMatrix(31,110) = groebnerMatrix(31,110) - factor * groebnerMatrix(18,182); groebnerMatrix(31,148) = groebnerMatrix(31,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(31,80); groebnerMatrix(31,80) = 0.0; groebnerMatrix(31,111) = groebnerMatrix(31,111) - factor * groebnerMatrix(18,182); groebnerMatrix(31,152) = groebnerMatrix(31,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(31,81); groebnerMatrix(31,81) = 0.0; groebnerMatrix(31,116) = groebnerMatrix(31,116) - factor * groebnerMatrix(18,182); groebnerMatrix(31,157) = groebnerMatrix(31,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(31,82); groebnerMatrix(31,82) = 0.0; groebnerMatrix(31,90) = groebnerMatrix(31,90) - factor * groebnerMatrix(12,171); groebnerMatrix(31,127) = groebnerMatrix(31,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,83); groebnerMatrix(31,83) = 0.0; groebnerMatrix(31,89) = groebnerMatrix(31,89) - factor * groebnerMatrix(20,170); groebnerMatrix(31,175) = groebnerMatrix(31,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(31,84); groebnerMatrix(31,84) = 0.0; groebnerMatrix(31,119) = groebnerMatrix(31,119) - factor * groebnerMatrix(17,179); groebnerMatrix(31,166) = groebnerMatrix(31,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(31,85); groebnerMatrix(31,85) = 0.0; groebnerMatrix(31,93) = groebnerMatrix(31,93) - factor * groebnerMatrix(11,174); groebnerMatrix(31,130) = groebnerMatrix(31,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(31,86); groebnerMatrix(31,86) = 0.0; groebnerMatrix(31,92) = groebnerMatrix(31,92) - factor * groebnerMatrix(21,173); groebnerMatrix(31,172) = groebnerMatrix(31,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(31,87); groebnerMatrix(31,87) = 0.0; groebnerMatrix(31,122) = groebnerMatrix(31,122) - factor * groebnerMatrix(18,182); groebnerMatrix(31,163) = groebnerMatrix(31,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(31,91); groebnerMatrix(31,91) = 0.0; groebnerMatrix(31,126) = groebnerMatrix(31,126) - factor * groebnerMatrix(17,179); groebnerMatrix(31,173) = groebnerMatrix(31,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(31,94); groebnerMatrix(31,94) = 0.0; groebnerMatrix(31,129) = groebnerMatrix(31,129) - factor * groebnerMatrix(18,182); groebnerMatrix(31,170) = groebnerMatrix(31,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(31,97); groebnerMatrix(31,97) = 0.0; groebnerMatrix(31,99) = groebnerMatrix(31,99) - factor * groebnerMatrix(15,144); groebnerMatrix(31,102) = groebnerMatrix(31,102) - factor * groebnerMatrix(15,147); groebnerMatrix(31,195) = groebnerMatrix(31,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(31,100); groebnerMatrix(31,100) = 0.0; groebnerMatrix(31,115) = groebnerMatrix(31,115) - factor * groebnerMatrix(24,160); groebnerMatrix(31,139) = groebnerMatrix(31,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(31,103); groebnerMatrix(31,103) = 0.0; groebnerMatrix(31,108) = groebnerMatrix(31,108) - factor * groebnerMatrix(14,153); groebnerMatrix(31,114) = groebnerMatrix(31,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(31,104); groebnerMatrix(31,104) = 0.0; groebnerMatrix(31,107) = groebnerMatrix(31,107) - factor * groebnerMatrix(19,152); groebnerMatrix(31,186) = groebnerMatrix(31,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(31,105); groebnerMatrix(31,105) = 0.0; groebnerMatrix(31,112) = groebnerMatrix(31,112) - factor * groebnerMatrix(28,157); groebnerMatrix(31,185) = groebnerMatrix(31,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(31,106); groebnerMatrix(31,106) = 0.0; groebnerMatrix(31,111) = groebnerMatrix(31,111) - factor * groebnerMatrix(13,156); groebnerMatrix(31,117) = groebnerMatrix(31,117) - factor * groebnerMatrix(13,162); groebnerMatrix(31,195) = groebnerMatrix(31,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(31,109); groebnerMatrix(31,109) = 0.0; groebnerMatrix(31,113) = groebnerMatrix(31,113) - factor * groebnerMatrix(16,158); groebnerMatrix(31,184) = groebnerMatrix(31,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(31,118); groebnerMatrix(31,118) = 0.0; groebnerMatrix(31,126) = groebnerMatrix(31,126) - factor * groebnerMatrix(12,171); groebnerMatrix(31,135) = groebnerMatrix(31,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,119); groebnerMatrix(31,119) = 0.0; groebnerMatrix(31,125) = groebnerMatrix(31,125) - factor * groebnerMatrix(20,170); groebnerMatrix(31,183) = groebnerMatrix(31,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(31,120); groebnerMatrix(31,120) = 0.0; groebnerMatrix(31,133) = groebnerMatrix(31,133) - factor * groebnerMatrix(29,178); groebnerMatrix(31,182) = groebnerMatrix(31,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(31,121); groebnerMatrix(31,121) = 0.0; groebnerMatrix(31,129) = groebnerMatrix(31,129) - factor * groebnerMatrix(11,174); groebnerMatrix(31,138) = groebnerMatrix(31,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(31,122); groebnerMatrix(31,122) = 0.0; groebnerMatrix(31,128) = groebnerMatrix(31,128) - factor * groebnerMatrix(21,173); groebnerMatrix(31,180) = groebnerMatrix(31,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(31,123); groebnerMatrix(31,123) = 0.0; groebnerMatrix(31,136) = groebnerMatrix(31,136) - factor * groebnerMatrix(27,181); groebnerMatrix(31,179) = groebnerMatrix(31,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(31,127); groebnerMatrix(31,127) = 0.0; groebnerMatrix(31,134) = groebnerMatrix(31,134) - factor * groebnerMatrix(17,179); groebnerMatrix(31,181) = groebnerMatrix(31,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(31,130); groebnerMatrix(31,130) = 0.0; groebnerMatrix(31,137) = groebnerMatrix(31,137) - factor * groebnerMatrix(18,182); groebnerMatrix(31,178) = groebnerMatrix(31,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(31,142); groebnerMatrix(31,142) = 0.0; groebnerMatrix(31,144) = groebnerMatrix(31,144) - factor * groebnerMatrix(15,144); groebnerMatrix(31,147) = groebnerMatrix(31,147) - factor * groebnerMatrix(15,147); groebnerMatrix(31,196) = groebnerMatrix(31,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(31,143); groebnerMatrix(31,143) = 0.0; groebnerMatrix(31,155) = groebnerMatrix(31,155) - factor * groebnerMatrix(26,155); groebnerMatrix(31,176) = groebnerMatrix(31,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(31,144); groebnerMatrix(31,144) = 0.0; groebnerMatrix(31,156) = groebnerMatrix(31,156) - factor * groebnerMatrix(25,156); groebnerMatrix(31,177) = groebnerMatrix(31,177) - factor * groebnerMatrix(25,177); groebnerMatrix(31,196) = groebnerMatrix(31,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(31,146); groebnerMatrix(31,146) = 0.0; groebnerMatrix(31,161) = groebnerMatrix(31,161) - factor * groebnerMatrix(23,161); groebnerMatrix(31,185) = groebnerMatrix(31,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(31,147); groebnerMatrix(31,147) = 0.0; groebnerMatrix(31,162) = groebnerMatrix(31,162) - factor * groebnerMatrix(22,162); groebnerMatrix(31,186) = groebnerMatrix(31,186) - factor * groebnerMatrix(22,186); groebnerMatrix(31,196) = groebnerMatrix(31,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(31,148); groebnerMatrix(31,148) = 0.0; groebnerMatrix(31,153) = groebnerMatrix(31,153) - factor * groebnerMatrix(14,153); groebnerMatrix(31,159) = groebnerMatrix(31,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(31,149); groebnerMatrix(31,149) = 0.0; groebnerMatrix(31,152) = groebnerMatrix(31,152) - factor * groebnerMatrix(19,152); groebnerMatrix(31,195) = groebnerMatrix(31,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(31,150); groebnerMatrix(31,150) = 0.0; groebnerMatrix(31,157) = groebnerMatrix(31,157) - factor * groebnerMatrix(28,157); groebnerMatrix(31,194) = groebnerMatrix(31,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(31,151); groebnerMatrix(31,151) = 0.0; groebnerMatrix(31,156) = groebnerMatrix(31,156) - factor * groebnerMatrix(13,156); groebnerMatrix(31,162) = groebnerMatrix(31,162) - factor * groebnerMatrix(13,162); groebnerMatrix(31,196) = groebnerMatrix(31,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,31); factor = -groebnerMatrix(31,154); groebnerMatrix(31,154) = 0.0; groebnerMatrix(31,158) = groebnerMatrix(31,158) - factor * groebnerMatrix(16,158); groebnerMatrix(31,193) = groebnerMatrix(31,193) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(31,163); groebnerMatrix(31,163) = 0.0; groebnerMatrix(31,171) = groebnerMatrix(31,171) - factor * groebnerMatrix(12,171); groebnerMatrix(31,180) = groebnerMatrix(31,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(31,164); groebnerMatrix(31,164) = 0.0; groebnerMatrix(31,170) = groebnerMatrix(31,170) - factor * groebnerMatrix(20,170); groebnerMatrix(31,192) = groebnerMatrix(31,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(31,165); groebnerMatrix(31,165) = 0.0; groebnerMatrix(31,178) = groebnerMatrix(31,178) - factor * groebnerMatrix(29,178); groebnerMatrix(31,191) = groebnerMatrix(31,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(31,166); groebnerMatrix(31,166) = 0.0; groebnerMatrix(31,174) = groebnerMatrix(31,174) - factor * groebnerMatrix(11,174); groebnerMatrix(31,183) = groebnerMatrix(31,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(31,167); groebnerMatrix(31,167) = 0.0; groebnerMatrix(31,173) = groebnerMatrix(31,173) - factor * groebnerMatrix(21,173); groebnerMatrix(31,189) = groebnerMatrix(31,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(31,168); groebnerMatrix(31,168) = 0.0; groebnerMatrix(31,181) = groebnerMatrix(31,181) - factor * groebnerMatrix(27,181); groebnerMatrix(31,188) = groebnerMatrix(31,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(31,169); groebnerMatrix(31,169) = 0.0; groebnerMatrix(31,177) = groebnerMatrix(31,177) - factor * groebnerMatrix(10,177); groebnerMatrix(31,186) = groebnerMatrix(31,186) - factor * groebnerMatrix(10,186); groebnerMatrix(31,196) = groebnerMatrix(31,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(31,172); groebnerMatrix(31,172) = 0.0; groebnerMatrix(31,179) = groebnerMatrix(31,179) - factor * groebnerMatrix(17,179); groebnerMatrix(31,190) = groebnerMatrix(31,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(31,175); groebnerMatrix(31,175) = 0.0; groebnerMatrix(31,182) = groebnerMatrix(31,182) - factor * groebnerMatrix(18,182); groebnerMatrix(31,187) = groebnerMatrix(31,187) - factor * groebnerMatrix(18,187); sPolynomial32(groebnerMatrix); factor = -groebnerMatrix(32,1); groebnerMatrix(32,1) = 0.0; groebnerMatrix(32,8) = groebnerMatrix(32,8) - factor * groebnerMatrix(19,152); groebnerMatrix(32,179) = groebnerMatrix(32,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(32,2); groebnerMatrix(32,2) = 0.0; groebnerMatrix(32,11) = groebnerMatrix(32,11) - factor * groebnerMatrix(14,153); groebnerMatrix(32,24) = groebnerMatrix(32,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(32,3); groebnerMatrix(32,3) = 0.0; groebnerMatrix(32,10) = groebnerMatrix(32,10) - factor * groebnerMatrix(19,152); groebnerMatrix(32,180) = groebnerMatrix(32,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(32,4); groebnerMatrix(32,4) = 0.0; groebnerMatrix(32,36) = groebnerMatrix(32,36) - factor * groebnerMatrix(22,162); groebnerMatrix(32,136) = groebnerMatrix(32,136) - factor * groebnerMatrix(22,186); groebnerMatrix(32,190) = groebnerMatrix(32,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(32,5); groebnerMatrix(32,5) = 0.0; groebnerMatrix(32,17) = groebnerMatrix(32,17) - factor * groebnerMatrix(13,156); groebnerMatrix(32,34) = groebnerMatrix(32,34) - factor * groebnerMatrix(13,162); groebnerMatrix(32,188) = groebnerMatrix(32,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(32,6); groebnerMatrix(32,6) = 0.0; groebnerMatrix(32,18) = groebnerMatrix(32,18) - factor * groebnerMatrix(13,156); groebnerMatrix(32,35) = groebnerMatrix(32,35) - factor * groebnerMatrix(13,162); groebnerMatrix(32,189) = groebnerMatrix(32,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(32,10); groebnerMatrix(32,10) = 0.0; groebnerMatrix(32,20) = groebnerMatrix(32,20) - factor * groebnerMatrix(16,158); groebnerMatrix(32,163) = groebnerMatrix(32,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(32,11); groebnerMatrix(32,11) = 0.0; groebnerMatrix(32,21) = groebnerMatrix(32,21) - factor * groebnerMatrix(16,158); groebnerMatrix(32,164) = groebnerMatrix(32,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(32,12); groebnerMatrix(32,12) = 0.0; groebnerMatrix(32,23) = groebnerMatrix(32,23) - factor * groebnerMatrix(16,158); groebnerMatrix(32,165) = groebnerMatrix(32,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(32,13); groebnerMatrix(32,13) = 0.0; groebnerMatrix(32,17) = groebnerMatrix(32,17) - factor * groebnerMatrix(14,153); groebnerMatrix(32,30) = groebnerMatrix(32,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(32,14); groebnerMatrix(32,14) = 0.0; groebnerMatrix(32,16) = groebnerMatrix(32,16) - factor * groebnerMatrix(19,152); groebnerMatrix(32,182) = groebnerMatrix(32,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(32,15); groebnerMatrix(32,15) = 0.0; groebnerMatrix(32,26) = groebnerMatrix(32,26) - factor * groebnerMatrix(16,158); groebnerMatrix(32,166) = groebnerMatrix(32,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(32,18); groebnerMatrix(32,18) = 0.0; groebnerMatrix(32,29) = groebnerMatrix(32,29) - factor * groebnerMatrix(16,158); groebnerMatrix(32,167) = groebnerMatrix(32,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(32,19); groebnerMatrix(32,19) = 0.0; groebnerMatrix(32,21) = groebnerMatrix(32,21) - factor * groebnerMatrix(15,144); groebnerMatrix(32,24) = groebnerMatrix(32,24) - factor * groebnerMatrix(15,147); groebnerMatrix(32,192) = groebnerMatrix(32,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(32,22); groebnerMatrix(32,22) = 0.0; groebnerMatrix(32,36) = groebnerMatrix(32,36) - factor * groebnerMatrix(24,160); groebnerMatrix(32,123) = groebnerMatrix(32,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(32,25); groebnerMatrix(32,25) = 0.0; groebnerMatrix(32,29) = groebnerMatrix(32,29) - factor * groebnerMatrix(14,153); groebnerMatrix(32,35) = groebnerMatrix(32,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(32,26); groebnerMatrix(32,26) = 0.0; groebnerMatrix(32,28) = groebnerMatrix(32,28) - factor * groebnerMatrix(19,152); groebnerMatrix(32,183) = groebnerMatrix(32,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(32,27); groebnerMatrix(32,27) = 0.0; groebnerMatrix(32,33) = groebnerMatrix(32,33) - factor * groebnerMatrix(28,157); groebnerMatrix(32,175) = groebnerMatrix(32,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(32,30); groebnerMatrix(32,30) = 0.0; groebnerMatrix(32,34) = groebnerMatrix(32,34) - factor * groebnerMatrix(16,158); groebnerMatrix(32,168) = groebnerMatrix(32,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(32,39); groebnerMatrix(32,39) = 0.0; groebnerMatrix(32,63) = groebnerMatrix(32,63) - factor * groebnerMatrix(12,171); groebnerMatrix(32,101) = groebnerMatrix(32,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,40); groebnerMatrix(32,40) = 0.0; groebnerMatrix(32,62) = groebnerMatrix(32,62) - factor * groebnerMatrix(20,170); groebnerMatrix(32,158) = groebnerMatrix(32,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(32,41); groebnerMatrix(32,41) = 0.0; groebnerMatrix(32,65) = groebnerMatrix(32,65) - factor * groebnerMatrix(12,171); groebnerMatrix(32,102) = groebnerMatrix(32,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,42); groebnerMatrix(32,42) = 0.0; groebnerMatrix(32,64) = groebnerMatrix(32,64) - factor * groebnerMatrix(20,170); groebnerMatrix(32,159) = groebnerMatrix(32,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(32,43); groebnerMatrix(32,43) = 0.0; groebnerMatrix(32,56) = groebnerMatrix(32,56) - factor * groebnerMatrix(22,162); groebnerMatrix(32,139) = groebnerMatrix(32,139) - factor * groebnerMatrix(22,186); groebnerMatrix(32,193) = groebnerMatrix(32,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(32,44); groebnerMatrix(32,44) = 0.0; groebnerMatrix(32,72) = groebnerMatrix(32,72) - factor * groebnerMatrix(11,174); groebnerMatrix(32,113) = groebnerMatrix(32,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(32,45); groebnerMatrix(32,45) = 0.0; groebnerMatrix(32,73) = groebnerMatrix(32,73) - factor * groebnerMatrix(11,174); groebnerMatrix(32,114) = groebnerMatrix(32,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(32,46); groebnerMatrix(32,46) = 0.0; groebnerMatrix(32,72) = groebnerMatrix(32,72) - factor * groebnerMatrix(12,171); groebnerMatrix(32,109) = groebnerMatrix(32,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,47); groebnerMatrix(32,47) = 0.0; groebnerMatrix(32,71) = groebnerMatrix(32,71) - factor * groebnerMatrix(20,170); groebnerMatrix(32,161) = groebnerMatrix(32,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(32,48); groebnerMatrix(32,48) = 0.0; groebnerMatrix(32,52) = groebnerMatrix(32,52) - factor * groebnerMatrix(16,158); groebnerMatrix(32,169) = groebnerMatrix(32,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(32,49); groebnerMatrix(32,49) = 0.0; groebnerMatrix(32,75) = groebnerMatrix(32,75) - factor * groebnerMatrix(11,174); groebnerMatrix(32,116) = groebnerMatrix(32,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(32,50); groebnerMatrix(32,50) = 0.0; groebnerMatrix(32,74) = groebnerMatrix(32,74) - factor * groebnerMatrix(21,173); groebnerMatrix(32,154) = groebnerMatrix(32,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(32,51); groebnerMatrix(32,51) = 0.0; groebnerMatrix(32,77) = groebnerMatrix(32,77) - factor * groebnerMatrix(12,171); groebnerMatrix(32,114) = groebnerMatrix(32,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,52); groebnerMatrix(32,52) = 0.0; groebnerMatrix(32,76) = groebnerMatrix(32,76) - factor * groebnerMatrix(20,170); groebnerMatrix(32,162) = groebnerMatrix(32,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(32,53); groebnerMatrix(32,53) = 0.0; groebnerMatrix(32,105) = groebnerMatrix(32,105) - factor * groebnerMatrix(27,181); groebnerMatrix(32,146) = groebnerMatrix(32,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(32,54); groebnerMatrix(32,54) = 0.0; groebnerMatrix(32,80) = groebnerMatrix(32,80) - factor * groebnerMatrix(11,174); groebnerMatrix(32,117) = groebnerMatrix(32,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(32,55); groebnerMatrix(32,55) = 0.0; groebnerMatrix(32,79) = groebnerMatrix(32,79) - factor * groebnerMatrix(21,173); groebnerMatrix(32,159) = groebnerMatrix(32,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(32,56); groebnerMatrix(32,56) = 0.0; groebnerMatrix(32,115) = groebnerMatrix(32,115) - factor * groebnerMatrix(27,181); groebnerMatrix(32,158) = groebnerMatrix(32,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(32,57); groebnerMatrix(32,57) = 0.0; groebnerMatrix(32,90) = groebnerMatrix(32,90) - factor * groebnerMatrix(10,177); groebnerMatrix(32,134) = groebnerMatrix(32,134) - factor * groebnerMatrix(10,186); groebnerMatrix(32,188) = groebnerMatrix(32,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(32,58); groebnerMatrix(32,58) = 0.0; groebnerMatrix(32,91) = groebnerMatrix(32,91) - factor * groebnerMatrix(10,177); groebnerMatrix(32,135) = groebnerMatrix(32,135) - factor * groebnerMatrix(10,186); groebnerMatrix(32,189) = groebnerMatrix(32,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(32,59); groebnerMatrix(32,59) = 0.0; groebnerMatrix(32,93) = groebnerMatrix(32,93) - factor * groebnerMatrix(10,177); groebnerMatrix(32,137) = groebnerMatrix(32,137) - factor * groebnerMatrix(10,186); groebnerMatrix(32,191) = groebnerMatrix(32,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(32,60); groebnerMatrix(32,60) = 0.0; groebnerMatrix(32,94) = groebnerMatrix(32,94) - factor * groebnerMatrix(10,177); groebnerMatrix(32,138) = groebnerMatrix(32,138) - factor * groebnerMatrix(10,186); groebnerMatrix(32,192) = groebnerMatrix(32,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(32,61); groebnerMatrix(32,61) = 0.0; groebnerMatrix(32,63) = groebnerMatrix(32,63) - factor * groebnerMatrix(15,144); groebnerMatrix(32,66) = groebnerMatrix(32,66) - factor * groebnerMatrix(15,147); groebnerMatrix(32,194) = groebnerMatrix(32,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(32,64); groebnerMatrix(32,64) = 0.0; groebnerMatrix(32,98) = groebnerMatrix(32,98) - factor * groebnerMatrix(17,179); groebnerMatrix(32,148) = groebnerMatrix(32,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(32,65); groebnerMatrix(32,65) = 0.0; groebnerMatrix(32,99) = groebnerMatrix(32,99) - factor * groebnerMatrix(17,179); groebnerMatrix(32,149) = groebnerMatrix(32,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(32,66); groebnerMatrix(32,66) = 0.0; groebnerMatrix(32,101) = groebnerMatrix(32,101) - factor * groebnerMatrix(17,179); groebnerMatrix(32,150) = groebnerMatrix(32,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(32,67); groebnerMatrix(32,67) = 0.0; groebnerMatrix(32,72) = groebnerMatrix(32,72) - factor * groebnerMatrix(14,153); groebnerMatrix(32,78) = groebnerMatrix(32,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(32,68); groebnerMatrix(32,68) = 0.0; groebnerMatrix(32,71) = groebnerMatrix(32,71) - factor * groebnerMatrix(19,152); groebnerMatrix(32,185) = groebnerMatrix(32,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(32,69); groebnerMatrix(32,69) = 0.0; groebnerMatrix(32,104) = groebnerMatrix(32,104) - factor * groebnerMatrix(17,179); groebnerMatrix(32,151) = groebnerMatrix(32,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(32,70); groebnerMatrix(32,70) = 0.0; groebnerMatrix(32,75) = groebnerMatrix(32,75) - factor * groebnerMatrix(13,156); groebnerMatrix(32,81) = groebnerMatrix(32,81) - factor * groebnerMatrix(13,162); groebnerMatrix(32,194) = groebnerMatrix(32,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(32,73); groebnerMatrix(32,73) = 0.0; groebnerMatrix(32,77) = groebnerMatrix(32,77) - factor * groebnerMatrix(16,158); groebnerMatrix(32,176) = groebnerMatrix(32,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(32,76); groebnerMatrix(32,76) = 0.0; groebnerMatrix(32,107) = groebnerMatrix(32,107) - factor * groebnerMatrix(18,182); groebnerMatrix(32,142) = groebnerMatrix(32,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(32,77); groebnerMatrix(32,77) = 0.0; groebnerMatrix(32,108) = groebnerMatrix(32,108) - factor * groebnerMatrix(18,182); groebnerMatrix(32,143) = groebnerMatrix(32,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(32,78); groebnerMatrix(32,78) = 0.0; groebnerMatrix(32,113) = groebnerMatrix(32,113) - factor * groebnerMatrix(17,179); groebnerMatrix(32,160) = groebnerMatrix(32,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(32,79); groebnerMatrix(32,79) = 0.0; groebnerMatrix(32,110) = groebnerMatrix(32,110) - factor * groebnerMatrix(18,182); groebnerMatrix(32,148) = groebnerMatrix(32,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(32,80); groebnerMatrix(32,80) = 0.0; groebnerMatrix(32,111) = groebnerMatrix(32,111) - factor * groebnerMatrix(18,182); groebnerMatrix(32,152) = groebnerMatrix(32,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(32,81); groebnerMatrix(32,81) = 0.0; groebnerMatrix(32,116) = groebnerMatrix(32,116) - factor * groebnerMatrix(18,182); groebnerMatrix(32,157) = groebnerMatrix(32,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(32,82); groebnerMatrix(32,82) = 0.0; groebnerMatrix(32,90) = groebnerMatrix(32,90) - factor * groebnerMatrix(12,171); groebnerMatrix(32,127) = groebnerMatrix(32,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,83); groebnerMatrix(32,83) = 0.0; groebnerMatrix(32,89) = groebnerMatrix(32,89) - factor * groebnerMatrix(20,170); groebnerMatrix(32,175) = groebnerMatrix(32,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(32,84); groebnerMatrix(32,84) = 0.0; groebnerMatrix(32,119) = groebnerMatrix(32,119) - factor * groebnerMatrix(17,179); groebnerMatrix(32,166) = groebnerMatrix(32,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(32,85); groebnerMatrix(32,85) = 0.0; groebnerMatrix(32,93) = groebnerMatrix(32,93) - factor * groebnerMatrix(11,174); groebnerMatrix(32,130) = groebnerMatrix(32,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(32,86); groebnerMatrix(32,86) = 0.0; groebnerMatrix(32,92) = groebnerMatrix(32,92) - factor * groebnerMatrix(21,173); groebnerMatrix(32,172) = groebnerMatrix(32,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(32,87); groebnerMatrix(32,87) = 0.0; groebnerMatrix(32,122) = groebnerMatrix(32,122) - factor * groebnerMatrix(18,182); groebnerMatrix(32,163) = groebnerMatrix(32,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(32,91); groebnerMatrix(32,91) = 0.0; groebnerMatrix(32,126) = groebnerMatrix(32,126) - factor * groebnerMatrix(17,179); groebnerMatrix(32,173) = groebnerMatrix(32,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(32,94); groebnerMatrix(32,94) = 0.0; groebnerMatrix(32,129) = groebnerMatrix(32,129) - factor * groebnerMatrix(18,182); groebnerMatrix(32,170) = groebnerMatrix(32,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(32,97); groebnerMatrix(32,97) = 0.0; groebnerMatrix(32,99) = groebnerMatrix(32,99) - factor * groebnerMatrix(15,144); groebnerMatrix(32,102) = groebnerMatrix(32,102) - factor * groebnerMatrix(15,147); groebnerMatrix(32,195) = groebnerMatrix(32,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(32,100); groebnerMatrix(32,100) = 0.0; groebnerMatrix(32,115) = groebnerMatrix(32,115) - factor * groebnerMatrix(24,160); groebnerMatrix(32,139) = groebnerMatrix(32,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(32,103); groebnerMatrix(32,103) = 0.0; groebnerMatrix(32,108) = groebnerMatrix(32,108) - factor * groebnerMatrix(14,153); groebnerMatrix(32,114) = groebnerMatrix(32,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(32,104); groebnerMatrix(32,104) = 0.0; groebnerMatrix(32,107) = groebnerMatrix(32,107) - factor * groebnerMatrix(19,152); groebnerMatrix(32,186) = groebnerMatrix(32,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(32,105); groebnerMatrix(32,105) = 0.0; groebnerMatrix(32,112) = groebnerMatrix(32,112) - factor * groebnerMatrix(28,157); groebnerMatrix(32,185) = groebnerMatrix(32,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(32,106); groebnerMatrix(32,106) = 0.0; groebnerMatrix(32,111) = groebnerMatrix(32,111) - factor * groebnerMatrix(13,156); groebnerMatrix(32,117) = groebnerMatrix(32,117) - factor * groebnerMatrix(13,162); groebnerMatrix(32,195) = groebnerMatrix(32,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(32,109); groebnerMatrix(32,109) = 0.0; groebnerMatrix(32,113) = groebnerMatrix(32,113) - factor * groebnerMatrix(16,158); groebnerMatrix(32,184) = groebnerMatrix(32,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(32,118); groebnerMatrix(32,118) = 0.0; groebnerMatrix(32,126) = groebnerMatrix(32,126) - factor * groebnerMatrix(12,171); groebnerMatrix(32,135) = groebnerMatrix(32,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,119); groebnerMatrix(32,119) = 0.0; groebnerMatrix(32,125) = groebnerMatrix(32,125) - factor * groebnerMatrix(20,170); groebnerMatrix(32,183) = groebnerMatrix(32,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(32,120); groebnerMatrix(32,120) = 0.0; groebnerMatrix(32,133) = groebnerMatrix(32,133) - factor * groebnerMatrix(29,178); groebnerMatrix(32,182) = groebnerMatrix(32,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(32,121); groebnerMatrix(32,121) = 0.0; groebnerMatrix(32,129) = groebnerMatrix(32,129) - factor * groebnerMatrix(11,174); groebnerMatrix(32,138) = groebnerMatrix(32,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(32,122); groebnerMatrix(32,122) = 0.0; groebnerMatrix(32,128) = groebnerMatrix(32,128) - factor * groebnerMatrix(21,173); groebnerMatrix(32,180) = groebnerMatrix(32,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(32,123); groebnerMatrix(32,123) = 0.0; groebnerMatrix(32,136) = groebnerMatrix(32,136) - factor * groebnerMatrix(27,181); groebnerMatrix(32,179) = groebnerMatrix(32,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(32,127); groebnerMatrix(32,127) = 0.0; groebnerMatrix(32,134) = groebnerMatrix(32,134) - factor * groebnerMatrix(17,179); groebnerMatrix(32,181) = groebnerMatrix(32,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(32,130); groebnerMatrix(32,130) = 0.0; groebnerMatrix(32,137) = groebnerMatrix(32,137) - factor * groebnerMatrix(18,182); groebnerMatrix(32,178) = groebnerMatrix(32,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(32,142); groebnerMatrix(32,142) = 0.0; groebnerMatrix(32,144) = groebnerMatrix(32,144) - factor * groebnerMatrix(15,144); groebnerMatrix(32,147) = groebnerMatrix(32,147) - factor * groebnerMatrix(15,147); groebnerMatrix(32,196) = groebnerMatrix(32,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(32,143); groebnerMatrix(32,143) = 0.0; groebnerMatrix(32,155) = groebnerMatrix(32,155) - factor * groebnerMatrix(26,155); groebnerMatrix(32,176) = groebnerMatrix(32,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(32,144); groebnerMatrix(32,144) = 0.0; groebnerMatrix(32,156) = groebnerMatrix(32,156) - factor * groebnerMatrix(25,156); groebnerMatrix(32,177) = groebnerMatrix(32,177) - factor * groebnerMatrix(25,177); groebnerMatrix(32,196) = groebnerMatrix(32,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(32,146); groebnerMatrix(32,146) = 0.0; groebnerMatrix(32,161) = groebnerMatrix(32,161) - factor * groebnerMatrix(23,161); groebnerMatrix(32,185) = groebnerMatrix(32,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(32,147); groebnerMatrix(32,147) = 0.0; groebnerMatrix(32,162) = groebnerMatrix(32,162) - factor * groebnerMatrix(22,162); groebnerMatrix(32,186) = groebnerMatrix(32,186) - factor * groebnerMatrix(22,186); groebnerMatrix(32,196) = groebnerMatrix(32,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(32,148); groebnerMatrix(32,148) = 0.0; groebnerMatrix(32,153) = groebnerMatrix(32,153) - factor * groebnerMatrix(14,153); groebnerMatrix(32,159) = groebnerMatrix(32,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(32,149); groebnerMatrix(32,149) = 0.0; groebnerMatrix(32,152) = groebnerMatrix(32,152) - factor * groebnerMatrix(19,152); groebnerMatrix(32,195) = groebnerMatrix(32,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(32,150); groebnerMatrix(32,150) = 0.0; groebnerMatrix(32,157) = groebnerMatrix(32,157) - factor * groebnerMatrix(28,157); groebnerMatrix(32,194) = groebnerMatrix(32,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(32,151); groebnerMatrix(32,151) = 0.0; groebnerMatrix(32,156) = groebnerMatrix(32,156) - factor * groebnerMatrix(13,156); groebnerMatrix(32,162) = groebnerMatrix(32,162) - factor * groebnerMatrix(13,162); groebnerMatrix(32,196) = groebnerMatrix(32,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,32); groebnerRow31_000000000_f(groebnerMatrix,32); factor = -groebnerMatrix(32,154); groebnerMatrix(32,154) = 0.0; groebnerMatrix(32,158) = groebnerMatrix(32,158) - factor * groebnerMatrix(16,158); groebnerMatrix(32,193) = groebnerMatrix(32,193) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(32,163); groebnerMatrix(32,163) = 0.0; groebnerMatrix(32,171) = groebnerMatrix(32,171) - factor * groebnerMatrix(12,171); groebnerMatrix(32,180) = groebnerMatrix(32,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(32,164); groebnerMatrix(32,164) = 0.0; groebnerMatrix(32,170) = groebnerMatrix(32,170) - factor * groebnerMatrix(20,170); groebnerMatrix(32,192) = groebnerMatrix(32,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(32,165); groebnerMatrix(32,165) = 0.0; groebnerMatrix(32,178) = groebnerMatrix(32,178) - factor * groebnerMatrix(29,178); groebnerMatrix(32,191) = groebnerMatrix(32,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(32,166); groebnerMatrix(32,166) = 0.0; groebnerMatrix(32,174) = groebnerMatrix(32,174) - factor * groebnerMatrix(11,174); groebnerMatrix(32,183) = groebnerMatrix(32,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(32,167); groebnerMatrix(32,167) = 0.0; groebnerMatrix(32,173) = groebnerMatrix(32,173) - factor * groebnerMatrix(21,173); groebnerMatrix(32,189) = groebnerMatrix(32,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(32,168); groebnerMatrix(32,168) = 0.0; groebnerMatrix(32,181) = groebnerMatrix(32,181) - factor * groebnerMatrix(27,181); groebnerMatrix(32,188) = groebnerMatrix(32,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(32,169); groebnerMatrix(32,169) = 0.0; groebnerMatrix(32,177) = groebnerMatrix(32,177) - factor * groebnerMatrix(10,177); groebnerMatrix(32,186) = groebnerMatrix(32,186) - factor * groebnerMatrix(10,186); groebnerMatrix(32,196) = groebnerMatrix(32,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(32,172); groebnerMatrix(32,172) = 0.0; groebnerMatrix(32,179) = groebnerMatrix(32,179) - factor * groebnerMatrix(17,179); groebnerMatrix(32,190) = groebnerMatrix(32,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(32,175); groebnerMatrix(32,175) = 0.0; groebnerMatrix(32,182) = groebnerMatrix(32,182) - factor * groebnerMatrix(18,182); groebnerMatrix(32,187) = groebnerMatrix(32,187) - factor * groebnerMatrix(18,187); sPolynomial33(groebnerMatrix); factor = -groebnerMatrix(33,1); groebnerMatrix(33,1) = 0.0; groebnerMatrix(33,8) = groebnerMatrix(33,8) - factor * groebnerMatrix(19,152); groebnerMatrix(33,179) = groebnerMatrix(33,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(33,2); groebnerMatrix(33,2) = 0.0; groebnerMatrix(33,11) = groebnerMatrix(33,11) - factor * groebnerMatrix(14,153); groebnerMatrix(33,24) = groebnerMatrix(33,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(33,3); groebnerMatrix(33,3) = 0.0; groebnerMatrix(33,10) = groebnerMatrix(33,10) - factor * groebnerMatrix(19,152); groebnerMatrix(33,180) = groebnerMatrix(33,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(33,4); groebnerMatrix(33,4) = 0.0; groebnerMatrix(33,36) = groebnerMatrix(33,36) - factor * groebnerMatrix(22,162); groebnerMatrix(33,136) = groebnerMatrix(33,136) - factor * groebnerMatrix(22,186); groebnerMatrix(33,190) = groebnerMatrix(33,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(33,5); groebnerMatrix(33,5) = 0.0; groebnerMatrix(33,17) = groebnerMatrix(33,17) - factor * groebnerMatrix(13,156); groebnerMatrix(33,34) = groebnerMatrix(33,34) - factor * groebnerMatrix(13,162); groebnerMatrix(33,188) = groebnerMatrix(33,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(33,6); groebnerMatrix(33,6) = 0.0; groebnerMatrix(33,18) = groebnerMatrix(33,18) - factor * groebnerMatrix(13,156); groebnerMatrix(33,35) = groebnerMatrix(33,35) - factor * groebnerMatrix(13,162); groebnerMatrix(33,189) = groebnerMatrix(33,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(33,10); groebnerMatrix(33,10) = 0.0; groebnerMatrix(33,20) = groebnerMatrix(33,20) - factor * groebnerMatrix(16,158); groebnerMatrix(33,163) = groebnerMatrix(33,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(33,11); groebnerMatrix(33,11) = 0.0; groebnerMatrix(33,21) = groebnerMatrix(33,21) - factor * groebnerMatrix(16,158); groebnerMatrix(33,164) = groebnerMatrix(33,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(33,12); groebnerMatrix(33,12) = 0.0; groebnerMatrix(33,23) = groebnerMatrix(33,23) - factor * groebnerMatrix(16,158); groebnerMatrix(33,165) = groebnerMatrix(33,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(33,13); groebnerMatrix(33,13) = 0.0; groebnerMatrix(33,17) = groebnerMatrix(33,17) - factor * groebnerMatrix(14,153); groebnerMatrix(33,30) = groebnerMatrix(33,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(33,14); groebnerMatrix(33,14) = 0.0; groebnerMatrix(33,16) = groebnerMatrix(33,16) - factor * groebnerMatrix(19,152); groebnerMatrix(33,182) = groebnerMatrix(33,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(33,15); groebnerMatrix(33,15) = 0.0; groebnerMatrix(33,26) = groebnerMatrix(33,26) - factor * groebnerMatrix(16,158); groebnerMatrix(33,166) = groebnerMatrix(33,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(33,18); groebnerMatrix(33,18) = 0.0; groebnerMatrix(33,29) = groebnerMatrix(33,29) - factor * groebnerMatrix(16,158); groebnerMatrix(33,167) = groebnerMatrix(33,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(33,19); groebnerMatrix(33,19) = 0.0; groebnerMatrix(33,21) = groebnerMatrix(33,21) - factor * groebnerMatrix(15,144); groebnerMatrix(33,24) = groebnerMatrix(33,24) - factor * groebnerMatrix(15,147); groebnerMatrix(33,192) = groebnerMatrix(33,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(33,22); groebnerMatrix(33,22) = 0.0; groebnerMatrix(33,36) = groebnerMatrix(33,36) - factor * groebnerMatrix(24,160); groebnerMatrix(33,123) = groebnerMatrix(33,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(33,25); groebnerMatrix(33,25) = 0.0; groebnerMatrix(33,29) = groebnerMatrix(33,29) - factor * groebnerMatrix(14,153); groebnerMatrix(33,35) = groebnerMatrix(33,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(33,26); groebnerMatrix(33,26) = 0.0; groebnerMatrix(33,28) = groebnerMatrix(33,28) - factor * groebnerMatrix(19,152); groebnerMatrix(33,183) = groebnerMatrix(33,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(33,27); groebnerMatrix(33,27) = 0.0; groebnerMatrix(33,33) = groebnerMatrix(33,33) - factor * groebnerMatrix(28,157); groebnerMatrix(33,175) = groebnerMatrix(33,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(33,30); groebnerMatrix(33,30) = 0.0; groebnerMatrix(33,34) = groebnerMatrix(33,34) - factor * groebnerMatrix(16,158); groebnerMatrix(33,168) = groebnerMatrix(33,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(33,39); groebnerMatrix(33,39) = 0.0; groebnerMatrix(33,63) = groebnerMatrix(33,63) - factor * groebnerMatrix(12,171); groebnerMatrix(33,101) = groebnerMatrix(33,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,40); groebnerMatrix(33,40) = 0.0; groebnerMatrix(33,62) = groebnerMatrix(33,62) - factor * groebnerMatrix(20,170); groebnerMatrix(33,158) = groebnerMatrix(33,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(33,41); groebnerMatrix(33,41) = 0.0; groebnerMatrix(33,65) = groebnerMatrix(33,65) - factor * groebnerMatrix(12,171); groebnerMatrix(33,102) = groebnerMatrix(33,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,42); groebnerMatrix(33,42) = 0.0; groebnerMatrix(33,64) = groebnerMatrix(33,64) - factor * groebnerMatrix(20,170); groebnerMatrix(33,159) = groebnerMatrix(33,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(33,43); groebnerMatrix(33,43) = 0.0; groebnerMatrix(33,56) = groebnerMatrix(33,56) - factor * groebnerMatrix(22,162); groebnerMatrix(33,139) = groebnerMatrix(33,139) - factor * groebnerMatrix(22,186); groebnerMatrix(33,193) = groebnerMatrix(33,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(33,44); groebnerMatrix(33,44) = 0.0; groebnerMatrix(33,72) = groebnerMatrix(33,72) - factor * groebnerMatrix(11,174); groebnerMatrix(33,113) = groebnerMatrix(33,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(33,45); groebnerMatrix(33,45) = 0.0; groebnerMatrix(33,73) = groebnerMatrix(33,73) - factor * groebnerMatrix(11,174); groebnerMatrix(33,114) = groebnerMatrix(33,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(33,46); groebnerMatrix(33,46) = 0.0; groebnerMatrix(33,72) = groebnerMatrix(33,72) - factor * groebnerMatrix(12,171); groebnerMatrix(33,109) = groebnerMatrix(33,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,47); groebnerMatrix(33,47) = 0.0; groebnerMatrix(33,71) = groebnerMatrix(33,71) - factor * groebnerMatrix(20,170); groebnerMatrix(33,161) = groebnerMatrix(33,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(33,48); groebnerMatrix(33,48) = 0.0; groebnerMatrix(33,52) = groebnerMatrix(33,52) - factor * groebnerMatrix(16,158); groebnerMatrix(33,169) = groebnerMatrix(33,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(33,49); groebnerMatrix(33,49) = 0.0; groebnerMatrix(33,75) = groebnerMatrix(33,75) - factor * groebnerMatrix(11,174); groebnerMatrix(33,116) = groebnerMatrix(33,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(33,50); groebnerMatrix(33,50) = 0.0; groebnerMatrix(33,74) = groebnerMatrix(33,74) - factor * groebnerMatrix(21,173); groebnerMatrix(33,154) = groebnerMatrix(33,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(33,51); groebnerMatrix(33,51) = 0.0; groebnerMatrix(33,77) = groebnerMatrix(33,77) - factor * groebnerMatrix(12,171); groebnerMatrix(33,114) = groebnerMatrix(33,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,52); groebnerMatrix(33,52) = 0.0; groebnerMatrix(33,76) = groebnerMatrix(33,76) - factor * groebnerMatrix(20,170); groebnerMatrix(33,162) = groebnerMatrix(33,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(33,53); groebnerMatrix(33,53) = 0.0; groebnerMatrix(33,105) = groebnerMatrix(33,105) - factor * groebnerMatrix(27,181); groebnerMatrix(33,146) = groebnerMatrix(33,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(33,54); groebnerMatrix(33,54) = 0.0; groebnerMatrix(33,80) = groebnerMatrix(33,80) - factor * groebnerMatrix(11,174); groebnerMatrix(33,117) = groebnerMatrix(33,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(33,55); groebnerMatrix(33,55) = 0.0; groebnerMatrix(33,79) = groebnerMatrix(33,79) - factor * groebnerMatrix(21,173); groebnerMatrix(33,159) = groebnerMatrix(33,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(33,56); groebnerMatrix(33,56) = 0.0; groebnerMatrix(33,115) = groebnerMatrix(33,115) - factor * groebnerMatrix(27,181); groebnerMatrix(33,158) = groebnerMatrix(33,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(33,57); groebnerMatrix(33,57) = 0.0; groebnerMatrix(33,90) = groebnerMatrix(33,90) - factor * groebnerMatrix(10,177); groebnerMatrix(33,134) = groebnerMatrix(33,134) - factor * groebnerMatrix(10,186); groebnerMatrix(33,188) = groebnerMatrix(33,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(33,58); groebnerMatrix(33,58) = 0.0; groebnerMatrix(33,91) = groebnerMatrix(33,91) - factor * groebnerMatrix(10,177); groebnerMatrix(33,135) = groebnerMatrix(33,135) - factor * groebnerMatrix(10,186); groebnerMatrix(33,189) = groebnerMatrix(33,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(33,59); groebnerMatrix(33,59) = 0.0; groebnerMatrix(33,93) = groebnerMatrix(33,93) - factor * groebnerMatrix(10,177); groebnerMatrix(33,137) = groebnerMatrix(33,137) - factor * groebnerMatrix(10,186); groebnerMatrix(33,191) = groebnerMatrix(33,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(33,60); groebnerMatrix(33,60) = 0.0; groebnerMatrix(33,94) = groebnerMatrix(33,94) - factor * groebnerMatrix(10,177); groebnerMatrix(33,138) = groebnerMatrix(33,138) - factor * groebnerMatrix(10,186); groebnerMatrix(33,192) = groebnerMatrix(33,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(33,61); groebnerMatrix(33,61) = 0.0; groebnerMatrix(33,63) = groebnerMatrix(33,63) - factor * groebnerMatrix(15,144); groebnerMatrix(33,66) = groebnerMatrix(33,66) - factor * groebnerMatrix(15,147); groebnerMatrix(33,194) = groebnerMatrix(33,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(33,64); groebnerMatrix(33,64) = 0.0; groebnerMatrix(33,98) = groebnerMatrix(33,98) - factor * groebnerMatrix(17,179); groebnerMatrix(33,148) = groebnerMatrix(33,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(33,65); groebnerMatrix(33,65) = 0.0; groebnerMatrix(33,99) = groebnerMatrix(33,99) - factor * groebnerMatrix(17,179); groebnerMatrix(33,149) = groebnerMatrix(33,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(33,66); groebnerMatrix(33,66) = 0.0; groebnerMatrix(33,101) = groebnerMatrix(33,101) - factor * groebnerMatrix(17,179); groebnerMatrix(33,150) = groebnerMatrix(33,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(33,67); groebnerMatrix(33,67) = 0.0; groebnerMatrix(33,72) = groebnerMatrix(33,72) - factor * groebnerMatrix(14,153); groebnerMatrix(33,78) = groebnerMatrix(33,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(33,68); groebnerMatrix(33,68) = 0.0; groebnerMatrix(33,71) = groebnerMatrix(33,71) - factor * groebnerMatrix(19,152); groebnerMatrix(33,185) = groebnerMatrix(33,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(33,69); groebnerMatrix(33,69) = 0.0; groebnerMatrix(33,104) = groebnerMatrix(33,104) - factor * groebnerMatrix(17,179); groebnerMatrix(33,151) = groebnerMatrix(33,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(33,70); groebnerMatrix(33,70) = 0.0; groebnerMatrix(33,75) = groebnerMatrix(33,75) - factor * groebnerMatrix(13,156); groebnerMatrix(33,81) = groebnerMatrix(33,81) - factor * groebnerMatrix(13,162); groebnerMatrix(33,194) = groebnerMatrix(33,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(33,73); groebnerMatrix(33,73) = 0.0; groebnerMatrix(33,77) = groebnerMatrix(33,77) - factor * groebnerMatrix(16,158); groebnerMatrix(33,176) = groebnerMatrix(33,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(33,76); groebnerMatrix(33,76) = 0.0; groebnerMatrix(33,107) = groebnerMatrix(33,107) - factor * groebnerMatrix(18,182); groebnerMatrix(33,142) = groebnerMatrix(33,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(33,77); groebnerMatrix(33,77) = 0.0; groebnerMatrix(33,108) = groebnerMatrix(33,108) - factor * groebnerMatrix(18,182); groebnerMatrix(33,143) = groebnerMatrix(33,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(33,78); groebnerMatrix(33,78) = 0.0; groebnerMatrix(33,113) = groebnerMatrix(33,113) - factor * groebnerMatrix(17,179); groebnerMatrix(33,160) = groebnerMatrix(33,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(33,79); groebnerMatrix(33,79) = 0.0; groebnerMatrix(33,110) = groebnerMatrix(33,110) - factor * groebnerMatrix(18,182); groebnerMatrix(33,148) = groebnerMatrix(33,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(33,80); groebnerMatrix(33,80) = 0.0; groebnerMatrix(33,111) = groebnerMatrix(33,111) - factor * groebnerMatrix(18,182); groebnerMatrix(33,152) = groebnerMatrix(33,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(33,81); groebnerMatrix(33,81) = 0.0; groebnerMatrix(33,116) = groebnerMatrix(33,116) - factor * groebnerMatrix(18,182); groebnerMatrix(33,157) = groebnerMatrix(33,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(33,82); groebnerMatrix(33,82) = 0.0; groebnerMatrix(33,90) = groebnerMatrix(33,90) - factor * groebnerMatrix(12,171); groebnerMatrix(33,127) = groebnerMatrix(33,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,83); groebnerMatrix(33,83) = 0.0; groebnerMatrix(33,89) = groebnerMatrix(33,89) - factor * groebnerMatrix(20,170); groebnerMatrix(33,175) = groebnerMatrix(33,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(33,84); groebnerMatrix(33,84) = 0.0; groebnerMatrix(33,119) = groebnerMatrix(33,119) - factor * groebnerMatrix(17,179); groebnerMatrix(33,166) = groebnerMatrix(33,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(33,85); groebnerMatrix(33,85) = 0.0; groebnerMatrix(33,93) = groebnerMatrix(33,93) - factor * groebnerMatrix(11,174); groebnerMatrix(33,130) = groebnerMatrix(33,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(33,86); groebnerMatrix(33,86) = 0.0; groebnerMatrix(33,92) = groebnerMatrix(33,92) - factor * groebnerMatrix(21,173); groebnerMatrix(33,172) = groebnerMatrix(33,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(33,87); groebnerMatrix(33,87) = 0.0; groebnerMatrix(33,122) = groebnerMatrix(33,122) - factor * groebnerMatrix(18,182); groebnerMatrix(33,163) = groebnerMatrix(33,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(33,91); groebnerMatrix(33,91) = 0.0; groebnerMatrix(33,126) = groebnerMatrix(33,126) - factor * groebnerMatrix(17,179); groebnerMatrix(33,173) = groebnerMatrix(33,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(33,94); groebnerMatrix(33,94) = 0.0; groebnerMatrix(33,129) = groebnerMatrix(33,129) - factor * groebnerMatrix(18,182); groebnerMatrix(33,170) = groebnerMatrix(33,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(33,97); groebnerMatrix(33,97) = 0.0; groebnerMatrix(33,99) = groebnerMatrix(33,99) - factor * groebnerMatrix(15,144); groebnerMatrix(33,102) = groebnerMatrix(33,102) - factor * groebnerMatrix(15,147); groebnerMatrix(33,195) = groebnerMatrix(33,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(33,100); groebnerMatrix(33,100) = 0.0; groebnerMatrix(33,115) = groebnerMatrix(33,115) - factor * groebnerMatrix(24,160); groebnerMatrix(33,139) = groebnerMatrix(33,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(33,103); groebnerMatrix(33,103) = 0.0; groebnerMatrix(33,108) = groebnerMatrix(33,108) - factor * groebnerMatrix(14,153); groebnerMatrix(33,114) = groebnerMatrix(33,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(33,104); groebnerMatrix(33,104) = 0.0; groebnerMatrix(33,107) = groebnerMatrix(33,107) - factor * groebnerMatrix(19,152); groebnerMatrix(33,186) = groebnerMatrix(33,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(33,105); groebnerMatrix(33,105) = 0.0; groebnerMatrix(33,112) = groebnerMatrix(33,112) - factor * groebnerMatrix(28,157); groebnerMatrix(33,185) = groebnerMatrix(33,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(33,106); groebnerMatrix(33,106) = 0.0; groebnerMatrix(33,111) = groebnerMatrix(33,111) - factor * groebnerMatrix(13,156); groebnerMatrix(33,117) = groebnerMatrix(33,117) - factor * groebnerMatrix(13,162); groebnerMatrix(33,195) = groebnerMatrix(33,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(33,109); groebnerMatrix(33,109) = 0.0; groebnerMatrix(33,113) = groebnerMatrix(33,113) - factor * groebnerMatrix(16,158); groebnerMatrix(33,184) = groebnerMatrix(33,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(33,118); groebnerMatrix(33,118) = 0.0; groebnerMatrix(33,126) = groebnerMatrix(33,126) - factor * groebnerMatrix(12,171); groebnerMatrix(33,135) = groebnerMatrix(33,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,119); groebnerMatrix(33,119) = 0.0; groebnerMatrix(33,125) = groebnerMatrix(33,125) - factor * groebnerMatrix(20,170); groebnerMatrix(33,183) = groebnerMatrix(33,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(33,120); groebnerMatrix(33,120) = 0.0; groebnerMatrix(33,133) = groebnerMatrix(33,133) - factor * groebnerMatrix(29,178); groebnerMatrix(33,182) = groebnerMatrix(33,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(33,121); groebnerMatrix(33,121) = 0.0; groebnerMatrix(33,129) = groebnerMatrix(33,129) - factor * groebnerMatrix(11,174); groebnerMatrix(33,138) = groebnerMatrix(33,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(33,122); groebnerMatrix(33,122) = 0.0; groebnerMatrix(33,128) = groebnerMatrix(33,128) - factor * groebnerMatrix(21,173); groebnerMatrix(33,180) = groebnerMatrix(33,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(33,123); groebnerMatrix(33,123) = 0.0; groebnerMatrix(33,136) = groebnerMatrix(33,136) - factor * groebnerMatrix(27,181); groebnerMatrix(33,179) = groebnerMatrix(33,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(33,127); groebnerMatrix(33,127) = 0.0; groebnerMatrix(33,134) = groebnerMatrix(33,134) - factor * groebnerMatrix(17,179); groebnerMatrix(33,181) = groebnerMatrix(33,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(33,130); groebnerMatrix(33,130) = 0.0; groebnerMatrix(33,137) = groebnerMatrix(33,137) - factor * groebnerMatrix(18,182); groebnerMatrix(33,178) = groebnerMatrix(33,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(33,142); groebnerMatrix(33,142) = 0.0; groebnerMatrix(33,144) = groebnerMatrix(33,144) - factor * groebnerMatrix(15,144); groebnerMatrix(33,147) = groebnerMatrix(33,147) - factor * groebnerMatrix(15,147); groebnerMatrix(33,196) = groebnerMatrix(33,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(33,143); groebnerMatrix(33,143) = 0.0; groebnerMatrix(33,155) = groebnerMatrix(33,155) - factor * groebnerMatrix(26,155); groebnerMatrix(33,176) = groebnerMatrix(33,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(33,144); groebnerMatrix(33,144) = 0.0; groebnerMatrix(33,156) = groebnerMatrix(33,156) - factor * groebnerMatrix(25,156); groebnerMatrix(33,177) = groebnerMatrix(33,177) - factor * groebnerMatrix(25,177); groebnerMatrix(33,196) = groebnerMatrix(33,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(33,146); groebnerMatrix(33,146) = 0.0; groebnerMatrix(33,161) = groebnerMatrix(33,161) - factor * groebnerMatrix(23,161); groebnerMatrix(33,185) = groebnerMatrix(33,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(33,147); groebnerMatrix(33,147) = 0.0; groebnerMatrix(33,162) = groebnerMatrix(33,162) - factor * groebnerMatrix(22,162); groebnerMatrix(33,186) = groebnerMatrix(33,186) - factor * groebnerMatrix(22,186); groebnerMatrix(33,196) = groebnerMatrix(33,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(33,148); groebnerMatrix(33,148) = 0.0; groebnerMatrix(33,153) = groebnerMatrix(33,153) - factor * groebnerMatrix(14,153); groebnerMatrix(33,159) = groebnerMatrix(33,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(33,149); groebnerMatrix(33,149) = 0.0; groebnerMatrix(33,152) = groebnerMatrix(33,152) - factor * groebnerMatrix(19,152); groebnerMatrix(33,195) = groebnerMatrix(33,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(33,150); groebnerMatrix(33,150) = 0.0; groebnerMatrix(33,157) = groebnerMatrix(33,157) - factor * groebnerMatrix(28,157); groebnerMatrix(33,194) = groebnerMatrix(33,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(33,151); groebnerMatrix(33,151) = 0.0; groebnerMatrix(33,156) = groebnerMatrix(33,156) - factor * groebnerMatrix(13,156); groebnerMatrix(33,162) = groebnerMatrix(33,162) - factor * groebnerMatrix(13,162); groebnerMatrix(33,196) = groebnerMatrix(33,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,33); groebnerRow31_000000000_f(groebnerMatrix,33); factor = -groebnerMatrix(33,154); groebnerMatrix(33,154) = 0.0; groebnerMatrix(33,158) = groebnerMatrix(33,158) - factor * groebnerMatrix(16,158); groebnerMatrix(33,193) = groebnerMatrix(33,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,33); factor = groebnerMatrix(33,163); groebnerMatrix(33,163) = 0.0; groebnerMatrix(33,171) = groebnerMatrix(33,171) - factor * groebnerMatrix(12,171); groebnerMatrix(33,180) = groebnerMatrix(33,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(33,164); groebnerMatrix(33,164) = 0.0; groebnerMatrix(33,170) = groebnerMatrix(33,170) - factor * groebnerMatrix(20,170); groebnerMatrix(33,192) = groebnerMatrix(33,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(33,165); groebnerMatrix(33,165) = 0.0; groebnerMatrix(33,178) = groebnerMatrix(33,178) - factor * groebnerMatrix(29,178); groebnerMatrix(33,191) = groebnerMatrix(33,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(33,166); groebnerMatrix(33,166) = 0.0; groebnerMatrix(33,174) = groebnerMatrix(33,174) - factor * groebnerMatrix(11,174); groebnerMatrix(33,183) = groebnerMatrix(33,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(33,167); groebnerMatrix(33,167) = 0.0; groebnerMatrix(33,173) = groebnerMatrix(33,173) - factor * groebnerMatrix(21,173); groebnerMatrix(33,189) = groebnerMatrix(33,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(33,168); groebnerMatrix(33,168) = 0.0; groebnerMatrix(33,181) = groebnerMatrix(33,181) - factor * groebnerMatrix(27,181); groebnerMatrix(33,188) = groebnerMatrix(33,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(33,169); groebnerMatrix(33,169) = 0.0; groebnerMatrix(33,177) = groebnerMatrix(33,177) - factor * groebnerMatrix(10,177); groebnerMatrix(33,186) = groebnerMatrix(33,186) - factor * groebnerMatrix(10,186); groebnerMatrix(33,196) = groebnerMatrix(33,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(33,172); groebnerMatrix(33,172) = 0.0; groebnerMatrix(33,179) = groebnerMatrix(33,179) - factor * groebnerMatrix(17,179); groebnerMatrix(33,190) = groebnerMatrix(33,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(33,175); groebnerMatrix(33,175) = 0.0; groebnerMatrix(33,182) = groebnerMatrix(33,182) - factor * groebnerMatrix(18,182); groebnerMatrix(33,187) = groebnerMatrix(33,187) - factor * groebnerMatrix(18,187); sPolynomial34(groebnerMatrix); factor = -groebnerMatrix(34,1); groebnerMatrix(34,1) = 0.0; groebnerMatrix(34,8) = groebnerMatrix(34,8) - factor * groebnerMatrix(19,152); groebnerMatrix(34,179) = groebnerMatrix(34,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(34,2); groebnerMatrix(34,2) = 0.0; groebnerMatrix(34,11) = groebnerMatrix(34,11) - factor * groebnerMatrix(14,153); groebnerMatrix(34,24) = groebnerMatrix(34,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(34,3); groebnerMatrix(34,3) = 0.0; groebnerMatrix(34,10) = groebnerMatrix(34,10) - factor * groebnerMatrix(19,152); groebnerMatrix(34,180) = groebnerMatrix(34,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(34,4); groebnerMatrix(34,4) = 0.0; groebnerMatrix(34,36) = groebnerMatrix(34,36) - factor * groebnerMatrix(22,162); groebnerMatrix(34,136) = groebnerMatrix(34,136) - factor * groebnerMatrix(22,186); groebnerMatrix(34,190) = groebnerMatrix(34,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(34,5); groebnerMatrix(34,5) = 0.0; groebnerMatrix(34,17) = groebnerMatrix(34,17) - factor * groebnerMatrix(13,156); groebnerMatrix(34,34) = groebnerMatrix(34,34) - factor * groebnerMatrix(13,162); groebnerMatrix(34,188) = groebnerMatrix(34,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(34,6); groebnerMatrix(34,6) = 0.0; groebnerMatrix(34,18) = groebnerMatrix(34,18) - factor * groebnerMatrix(13,156); groebnerMatrix(34,35) = groebnerMatrix(34,35) - factor * groebnerMatrix(13,162); groebnerMatrix(34,189) = groebnerMatrix(34,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(34,10); groebnerMatrix(34,10) = 0.0; groebnerMatrix(34,20) = groebnerMatrix(34,20) - factor * groebnerMatrix(16,158); groebnerMatrix(34,163) = groebnerMatrix(34,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(34,11); groebnerMatrix(34,11) = 0.0; groebnerMatrix(34,21) = groebnerMatrix(34,21) - factor * groebnerMatrix(16,158); groebnerMatrix(34,164) = groebnerMatrix(34,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(34,12); groebnerMatrix(34,12) = 0.0; groebnerMatrix(34,23) = groebnerMatrix(34,23) - factor * groebnerMatrix(16,158); groebnerMatrix(34,165) = groebnerMatrix(34,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(34,13); groebnerMatrix(34,13) = 0.0; groebnerMatrix(34,17) = groebnerMatrix(34,17) - factor * groebnerMatrix(14,153); groebnerMatrix(34,30) = groebnerMatrix(34,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(34,14); groebnerMatrix(34,14) = 0.0; groebnerMatrix(34,16) = groebnerMatrix(34,16) - factor * groebnerMatrix(19,152); groebnerMatrix(34,182) = groebnerMatrix(34,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(34,15); groebnerMatrix(34,15) = 0.0; groebnerMatrix(34,26) = groebnerMatrix(34,26) - factor * groebnerMatrix(16,158); groebnerMatrix(34,166) = groebnerMatrix(34,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(34,18); groebnerMatrix(34,18) = 0.0; groebnerMatrix(34,29) = groebnerMatrix(34,29) - factor * groebnerMatrix(16,158); groebnerMatrix(34,167) = groebnerMatrix(34,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(34,19); groebnerMatrix(34,19) = 0.0; groebnerMatrix(34,21) = groebnerMatrix(34,21) - factor * groebnerMatrix(15,144); groebnerMatrix(34,24) = groebnerMatrix(34,24) - factor * groebnerMatrix(15,147); groebnerMatrix(34,192) = groebnerMatrix(34,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(34,22); groebnerMatrix(34,22) = 0.0; groebnerMatrix(34,36) = groebnerMatrix(34,36) - factor * groebnerMatrix(24,160); groebnerMatrix(34,123) = groebnerMatrix(34,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(34,25); groebnerMatrix(34,25) = 0.0; groebnerMatrix(34,29) = groebnerMatrix(34,29) - factor * groebnerMatrix(14,153); groebnerMatrix(34,35) = groebnerMatrix(34,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(34,26); groebnerMatrix(34,26) = 0.0; groebnerMatrix(34,28) = groebnerMatrix(34,28) - factor * groebnerMatrix(19,152); groebnerMatrix(34,183) = groebnerMatrix(34,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(34,27); groebnerMatrix(34,27) = 0.0; groebnerMatrix(34,33) = groebnerMatrix(34,33) - factor * groebnerMatrix(28,157); groebnerMatrix(34,175) = groebnerMatrix(34,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(34,30); groebnerMatrix(34,30) = 0.0; groebnerMatrix(34,34) = groebnerMatrix(34,34) - factor * groebnerMatrix(16,158); groebnerMatrix(34,168) = groebnerMatrix(34,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(34,39); groebnerMatrix(34,39) = 0.0; groebnerMatrix(34,63) = groebnerMatrix(34,63) - factor * groebnerMatrix(12,171); groebnerMatrix(34,101) = groebnerMatrix(34,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,40); groebnerMatrix(34,40) = 0.0; groebnerMatrix(34,62) = groebnerMatrix(34,62) - factor * groebnerMatrix(20,170); groebnerMatrix(34,158) = groebnerMatrix(34,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(34,41); groebnerMatrix(34,41) = 0.0; groebnerMatrix(34,65) = groebnerMatrix(34,65) - factor * groebnerMatrix(12,171); groebnerMatrix(34,102) = groebnerMatrix(34,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,42); groebnerMatrix(34,42) = 0.0; groebnerMatrix(34,64) = groebnerMatrix(34,64) - factor * groebnerMatrix(20,170); groebnerMatrix(34,159) = groebnerMatrix(34,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(34,43); groebnerMatrix(34,43) = 0.0; groebnerMatrix(34,56) = groebnerMatrix(34,56) - factor * groebnerMatrix(22,162); groebnerMatrix(34,139) = groebnerMatrix(34,139) - factor * groebnerMatrix(22,186); groebnerMatrix(34,193) = groebnerMatrix(34,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(34,44); groebnerMatrix(34,44) = 0.0; groebnerMatrix(34,72) = groebnerMatrix(34,72) - factor * groebnerMatrix(11,174); groebnerMatrix(34,113) = groebnerMatrix(34,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(34,45); groebnerMatrix(34,45) = 0.0; groebnerMatrix(34,73) = groebnerMatrix(34,73) - factor * groebnerMatrix(11,174); groebnerMatrix(34,114) = groebnerMatrix(34,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(34,46); groebnerMatrix(34,46) = 0.0; groebnerMatrix(34,72) = groebnerMatrix(34,72) - factor * groebnerMatrix(12,171); groebnerMatrix(34,109) = groebnerMatrix(34,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,47); groebnerMatrix(34,47) = 0.0; groebnerMatrix(34,71) = groebnerMatrix(34,71) - factor * groebnerMatrix(20,170); groebnerMatrix(34,161) = groebnerMatrix(34,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(34,48); groebnerMatrix(34,48) = 0.0; groebnerMatrix(34,52) = groebnerMatrix(34,52) - factor * groebnerMatrix(16,158); groebnerMatrix(34,169) = groebnerMatrix(34,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(34,49); groebnerMatrix(34,49) = 0.0; groebnerMatrix(34,75) = groebnerMatrix(34,75) - factor * groebnerMatrix(11,174); groebnerMatrix(34,116) = groebnerMatrix(34,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(34,50); groebnerMatrix(34,50) = 0.0; groebnerMatrix(34,74) = groebnerMatrix(34,74) - factor * groebnerMatrix(21,173); groebnerMatrix(34,154) = groebnerMatrix(34,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(34,51); groebnerMatrix(34,51) = 0.0; groebnerMatrix(34,77) = groebnerMatrix(34,77) - factor * groebnerMatrix(12,171); groebnerMatrix(34,114) = groebnerMatrix(34,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,52); groebnerMatrix(34,52) = 0.0; groebnerMatrix(34,76) = groebnerMatrix(34,76) - factor * groebnerMatrix(20,170); groebnerMatrix(34,162) = groebnerMatrix(34,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(34,53); groebnerMatrix(34,53) = 0.0; groebnerMatrix(34,105) = groebnerMatrix(34,105) - factor * groebnerMatrix(27,181); groebnerMatrix(34,146) = groebnerMatrix(34,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(34,54); groebnerMatrix(34,54) = 0.0; groebnerMatrix(34,80) = groebnerMatrix(34,80) - factor * groebnerMatrix(11,174); groebnerMatrix(34,117) = groebnerMatrix(34,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(34,55); groebnerMatrix(34,55) = 0.0; groebnerMatrix(34,79) = groebnerMatrix(34,79) - factor * groebnerMatrix(21,173); groebnerMatrix(34,159) = groebnerMatrix(34,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(34,56); groebnerMatrix(34,56) = 0.0; groebnerMatrix(34,115) = groebnerMatrix(34,115) - factor * groebnerMatrix(27,181); groebnerMatrix(34,158) = groebnerMatrix(34,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(34,57); groebnerMatrix(34,57) = 0.0; groebnerMatrix(34,90) = groebnerMatrix(34,90) - factor * groebnerMatrix(10,177); groebnerMatrix(34,134) = groebnerMatrix(34,134) - factor * groebnerMatrix(10,186); groebnerMatrix(34,188) = groebnerMatrix(34,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(34,58); groebnerMatrix(34,58) = 0.0; groebnerMatrix(34,91) = groebnerMatrix(34,91) - factor * groebnerMatrix(10,177); groebnerMatrix(34,135) = groebnerMatrix(34,135) - factor * groebnerMatrix(10,186); groebnerMatrix(34,189) = groebnerMatrix(34,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(34,59); groebnerMatrix(34,59) = 0.0; groebnerMatrix(34,93) = groebnerMatrix(34,93) - factor * groebnerMatrix(10,177); groebnerMatrix(34,137) = groebnerMatrix(34,137) - factor * groebnerMatrix(10,186); groebnerMatrix(34,191) = groebnerMatrix(34,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(34,60); groebnerMatrix(34,60) = 0.0; groebnerMatrix(34,94) = groebnerMatrix(34,94) - factor * groebnerMatrix(10,177); groebnerMatrix(34,138) = groebnerMatrix(34,138) - factor * groebnerMatrix(10,186); groebnerMatrix(34,192) = groebnerMatrix(34,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(34,61); groebnerMatrix(34,61) = 0.0; groebnerMatrix(34,63) = groebnerMatrix(34,63) - factor * groebnerMatrix(15,144); groebnerMatrix(34,66) = groebnerMatrix(34,66) - factor * groebnerMatrix(15,147); groebnerMatrix(34,194) = groebnerMatrix(34,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(34,64); groebnerMatrix(34,64) = 0.0; groebnerMatrix(34,98) = groebnerMatrix(34,98) - factor * groebnerMatrix(17,179); groebnerMatrix(34,148) = groebnerMatrix(34,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(34,65); groebnerMatrix(34,65) = 0.0; groebnerMatrix(34,99) = groebnerMatrix(34,99) - factor * groebnerMatrix(17,179); groebnerMatrix(34,149) = groebnerMatrix(34,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(34,66); groebnerMatrix(34,66) = 0.0; groebnerMatrix(34,101) = groebnerMatrix(34,101) - factor * groebnerMatrix(17,179); groebnerMatrix(34,150) = groebnerMatrix(34,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(34,67); groebnerMatrix(34,67) = 0.0; groebnerMatrix(34,72) = groebnerMatrix(34,72) - factor * groebnerMatrix(14,153); groebnerMatrix(34,78) = groebnerMatrix(34,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(34,68); groebnerMatrix(34,68) = 0.0; groebnerMatrix(34,71) = groebnerMatrix(34,71) - factor * groebnerMatrix(19,152); groebnerMatrix(34,185) = groebnerMatrix(34,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(34,69); groebnerMatrix(34,69) = 0.0; groebnerMatrix(34,104) = groebnerMatrix(34,104) - factor * groebnerMatrix(17,179); groebnerMatrix(34,151) = groebnerMatrix(34,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(34,70); groebnerMatrix(34,70) = 0.0; groebnerMatrix(34,75) = groebnerMatrix(34,75) - factor * groebnerMatrix(13,156); groebnerMatrix(34,81) = groebnerMatrix(34,81) - factor * groebnerMatrix(13,162); groebnerMatrix(34,194) = groebnerMatrix(34,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(34,73); groebnerMatrix(34,73) = 0.0; groebnerMatrix(34,77) = groebnerMatrix(34,77) - factor * groebnerMatrix(16,158); groebnerMatrix(34,176) = groebnerMatrix(34,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(34,76); groebnerMatrix(34,76) = 0.0; groebnerMatrix(34,107) = groebnerMatrix(34,107) - factor * groebnerMatrix(18,182); groebnerMatrix(34,142) = groebnerMatrix(34,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(34,77); groebnerMatrix(34,77) = 0.0; groebnerMatrix(34,108) = groebnerMatrix(34,108) - factor * groebnerMatrix(18,182); groebnerMatrix(34,143) = groebnerMatrix(34,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(34,78); groebnerMatrix(34,78) = 0.0; groebnerMatrix(34,113) = groebnerMatrix(34,113) - factor * groebnerMatrix(17,179); groebnerMatrix(34,160) = groebnerMatrix(34,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(34,79); groebnerMatrix(34,79) = 0.0; groebnerMatrix(34,110) = groebnerMatrix(34,110) - factor * groebnerMatrix(18,182); groebnerMatrix(34,148) = groebnerMatrix(34,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(34,80); groebnerMatrix(34,80) = 0.0; groebnerMatrix(34,111) = groebnerMatrix(34,111) - factor * groebnerMatrix(18,182); groebnerMatrix(34,152) = groebnerMatrix(34,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(34,81); groebnerMatrix(34,81) = 0.0; groebnerMatrix(34,116) = groebnerMatrix(34,116) - factor * groebnerMatrix(18,182); groebnerMatrix(34,157) = groebnerMatrix(34,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(34,82); groebnerMatrix(34,82) = 0.0; groebnerMatrix(34,90) = groebnerMatrix(34,90) - factor * groebnerMatrix(12,171); groebnerMatrix(34,127) = groebnerMatrix(34,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,83); groebnerMatrix(34,83) = 0.0; groebnerMatrix(34,89) = groebnerMatrix(34,89) - factor * groebnerMatrix(20,170); groebnerMatrix(34,175) = groebnerMatrix(34,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(34,84); groebnerMatrix(34,84) = 0.0; groebnerMatrix(34,119) = groebnerMatrix(34,119) - factor * groebnerMatrix(17,179); groebnerMatrix(34,166) = groebnerMatrix(34,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(34,85); groebnerMatrix(34,85) = 0.0; groebnerMatrix(34,93) = groebnerMatrix(34,93) - factor * groebnerMatrix(11,174); groebnerMatrix(34,130) = groebnerMatrix(34,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(34,86); groebnerMatrix(34,86) = 0.0; groebnerMatrix(34,92) = groebnerMatrix(34,92) - factor * groebnerMatrix(21,173); groebnerMatrix(34,172) = groebnerMatrix(34,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(34,87); groebnerMatrix(34,87) = 0.0; groebnerMatrix(34,122) = groebnerMatrix(34,122) - factor * groebnerMatrix(18,182); groebnerMatrix(34,163) = groebnerMatrix(34,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(34,91); groebnerMatrix(34,91) = 0.0; groebnerMatrix(34,126) = groebnerMatrix(34,126) - factor * groebnerMatrix(17,179); groebnerMatrix(34,173) = groebnerMatrix(34,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(34,94); groebnerMatrix(34,94) = 0.0; groebnerMatrix(34,129) = groebnerMatrix(34,129) - factor * groebnerMatrix(18,182); groebnerMatrix(34,170) = groebnerMatrix(34,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(34,97); groebnerMatrix(34,97) = 0.0; groebnerMatrix(34,99) = groebnerMatrix(34,99) - factor * groebnerMatrix(15,144); groebnerMatrix(34,102) = groebnerMatrix(34,102) - factor * groebnerMatrix(15,147); groebnerMatrix(34,195) = groebnerMatrix(34,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(34,100); groebnerMatrix(34,100) = 0.0; groebnerMatrix(34,115) = groebnerMatrix(34,115) - factor * groebnerMatrix(24,160); groebnerMatrix(34,139) = groebnerMatrix(34,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(34,103); groebnerMatrix(34,103) = 0.0; groebnerMatrix(34,108) = groebnerMatrix(34,108) - factor * groebnerMatrix(14,153); groebnerMatrix(34,114) = groebnerMatrix(34,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(34,104); groebnerMatrix(34,104) = 0.0; groebnerMatrix(34,107) = groebnerMatrix(34,107) - factor * groebnerMatrix(19,152); groebnerMatrix(34,186) = groebnerMatrix(34,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(34,105); groebnerMatrix(34,105) = 0.0; groebnerMatrix(34,112) = groebnerMatrix(34,112) - factor * groebnerMatrix(28,157); groebnerMatrix(34,185) = groebnerMatrix(34,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(34,106); groebnerMatrix(34,106) = 0.0; groebnerMatrix(34,111) = groebnerMatrix(34,111) - factor * groebnerMatrix(13,156); groebnerMatrix(34,117) = groebnerMatrix(34,117) - factor * groebnerMatrix(13,162); groebnerMatrix(34,195) = groebnerMatrix(34,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(34,109); groebnerMatrix(34,109) = 0.0; groebnerMatrix(34,113) = groebnerMatrix(34,113) - factor * groebnerMatrix(16,158); groebnerMatrix(34,184) = groebnerMatrix(34,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(34,118); groebnerMatrix(34,118) = 0.0; groebnerMatrix(34,126) = groebnerMatrix(34,126) - factor * groebnerMatrix(12,171); groebnerMatrix(34,135) = groebnerMatrix(34,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,119); groebnerMatrix(34,119) = 0.0; groebnerMatrix(34,125) = groebnerMatrix(34,125) - factor * groebnerMatrix(20,170); groebnerMatrix(34,183) = groebnerMatrix(34,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(34,120); groebnerMatrix(34,120) = 0.0; groebnerMatrix(34,133) = groebnerMatrix(34,133) - factor * groebnerMatrix(29,178); groebnerMatrix(34,182) = groebnerMatrix(34,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(34,121); groebnerMatrix(34,121) = 0.0; groebnerMatrix(34,129) = groebnerMatrix(34,129) - factor * groebnerMatrix(11,174); groebnerMatrix(34,138) = groebnerMatrix(34,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(34,122); groebnerMatrix(34,122) = 0.0; groebnerMatrix(34,128) = groebnerMatrix(34,128) - factor * groebnerMatrix(21,173); groebnerMatrix(34,180) = groebnerMatrix(34,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(34,123); groebnerMatrix(34,123) = 0.0; groebnerMatrix(34,136) = groebnerMatrix(34,136) - factor * groebnerMatrix(27,181); groebnerMatrix(34,179) = groebnerMatrix(34,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(34,127); groebnerMatrix(34,127) = 0.0; groebnerMatrix(34,134) = groebnerMatrix(34,134) - factor * groebnerMatrix(17,179); groebnerMatrix(34,181) = groebnerMatrix(34,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(34,130); groebnerMatrix(34,130) = 0.0; groebnerMatrix(34,137) = groebnerMatrix(34,137) - factor * groebnerMatrix(18,182); groebnerMatrix(34,178) = groebnerMatrix(34,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(34,142); groebnerMatrix(34,142) = 0.0; groebnerMatrix(34,144) = groebnerMatrix(34,144) - factor * groebnerMatrix(15,144); groebnerMatrix(34,147) = groebnerMatrix(34,147) - factor * groebnerMatrix(15,147); groebnerMatrix(34,196) = groebnerMatrix(34,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(34,143); groebnerMatrix(34,143) = 0.0; groebnerMatrix(34,155) = groebnerMatrix(34,155) - factor * groebnerMatrix(26,155); groebnerMatrix(34,176) = groebnerMatrix(34,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(34,144); groebnerMatrix(34,144) = 0.0; groebnerMatrix(34,156) = groebnerMatrix(34,156) - factor * groebnerMatrix(25,156); groebnerMatrix(34,177) = groebnerMatrix(34,177) - factor * groebnerMatrix(25,177); groebnerMatrix(34,196) = groebnerMatrix(34,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(34,146); groebnerMatrix(34,146) = 0.0; groebnerMatrix(34,161) = groebnerMatrix(34,161) - factor * groebnerMatrix(23,161); groebnerMatrix(34,185) = groebnerMatrix(34,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(34,147); groebnerMatrix(34,147) = 0.0; groebnerMatrix(34,162) = groebnerMatrix(34,162) - factor * groebnerMatrix(22,162); groebnerMatrix(34,186) = groebnerMatrix(34,186) - factor * groebnerMatrix(22,186); groebnerMatrix(34,196) = groebnerMatrix(34,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(34,148); groebnerMatrix(34,148) = 0.0; groebnerMatrix(34,153) = groebnerMatrix(34,153) - factor * groebnerMatrix(14,153); groebnerMatrix(34,159) = groebnerMatrix(34,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(34,149); groebnerMatrix(34,149) = 0.0; groebnerMatrix(34,152) = groebnerMatrix(34,152) - factor * groebnerMatrix(19,152); groebnerMatrix(34,195) = groebnerMatrix(34,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(34,150); groebnerMatrix(34,150) = 0.0; groebnerMatrix(34,157) = groebnerMatrix(34,157) - factor * groebnerMatrix(28,157); groebnerMatrix(34,194) = groebnerMatrix(34,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(34,151); groebnerMatrix(34,151) = 0.0; groebnerMatrix(34,156) = groebnerMatrix(34,156) - factor * groebnerMatrix(13,156); groebnerMatrix(34,162) = groebnerMatrix(34,162) - factor * groebnerMatrix(13,162); groebnerMatrix(34,196) = groebnerMatrix(34,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,34); groebnerRow31_000000000_f(groebnerMatrix,34); factor = -groebnerMatrix(34,154); groebnerMatrix(34,154) = 0.0; groebnerMatrix(34,158) = groebnerMatrix(34,158) - factor * groebnerMatrix(16,158); groebnerMatrix(34,193) = groebnerMatrix(34,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,34); groebnerRow33_000000000_f(groebnerMatrix,34); factor = groebnerMatrix(34,163); groebnerMatrix(34,163) = 0.0; groebnerMatrix(34,171) = groebnerMatrix(34,171) - factor * groebnerMatrix(12,171); groebnerMatrix(34,180) = groebnerMatrix(34,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(34,164); groebnerMatrix(34,164) = 0.0; groebnerMatrix(34,170) = groebnerMatrix(34,170) - factor * groebnerMatrix(20,170); groebnerMatrix(34,192) = groebnerMatrix(34,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(34,165); groebnerMatrix(34,165) = 0.0; groebnerMatrix(34,178) = groebnerMatrix(34,178) - factor * groebnerMatrix(29,178); groebnerMatrix(34,191) = groebnerMatrix(34,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(34,166); groebnerMatrix(34,166) = 0.0; groebnerMatrix(34,174) = groebnerMatrix(34,174) - factor * groebnerMatrix(11,174); groebnerMatrix(34,183) = groebnerMatrix(34,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(34,167); groebnerMatrix(34,167) = 0.0; groebnerMatrix(34,173) = groebnerMatrix(34,173) - factor * groebnerMatrix(21,173); groebnerMatrix(34,189) = groebnerMatrix(34,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(34,168); groebnerMatrix(34,168) = 0.0; groebnerMatrix(34,181) = groebnerMatrix(34,181) - factor * groebnerMatrix(27,181); groebnerMatrix(34,188) = groebnerMatrix(34,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(34,169); groebnerMatrix(34,169) = 0.0; groebnerMatrix(34,177) = groebnerMatrix(34,177) - factor * groebnerMatrix(10,177); groebnerMatrix(34,186) = groebnerMatrix(34,186) - factor * groebnerMatrix(10,186); groebnerMatrix(34,196) = groebnerMatrix(34,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(34,172); groebnerMatrix(34,172) = 0.0; groebnerMatrix(34,179) = groebnerMatrix(34,179) - factor * groebnerMatrix(17,179); groebnerMatrix(34,190) = groebnerMatrix(34,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(34,175); groebnerMatrix(34,175) = 0.0; groebnerMatrix(34,182) = groebnerMatrix(34,182) - factor * groebnerMatrix(18,182); groebnerMatrix(34,187) = groebnerMatrix(34,187) - factor * groebnerMatrix(18,187); sPolynomial35(groebnerMatrix); factor = -groebnerMatrix(35,1); groebnerMatrix(35,1) = 0.0; groebnerMatrix(35,8) = groebnerMatrix(35,8) - factor * groebnerMatrix(19,152); groebnerMatrix(35,179) = groebnerMatrix(35,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(35,2); groebnerMatrix(35,2) = 0.0; groebnerMatrix(35,11) = groebnerMatrix(35,11) - factor * groebnerMatrix(14,153); groebnerMatrix(35,24) = groebnerMatrix(35,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(35,3); groebnerMatrix(35,3) = 0.0; groebnerMatrix(35,10) = groebnerMatrix(35,10) - factor * groebnerMatrix(19,152); groebnerMatrix(35,180) = groebnerMatrix(35,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(35,4); groebnerMatrix(35,4) = 0.0; groebnerMatrix(35,36) = groebnerMatrix(35,36) - factor * groebnerMatrix(22,162); groebnerMatrix(35,136) = groebnerMatrix(35,136) - factor * groebnerMatrix(22,186); groebnerMatrix(35,190) = groebnerMatrix(35,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(35,5); groebnerMatrix(35,5) = 0.0; groebnerMatrix(35,17) = groebnerMatrix(35,17) - factor * groebnerMatrix(13,156); groebnerMatrix(35,34) = groebnerMatrix(35,34) - factor * groebnerMatrix(13,162); groebnerMatrix(35,188) = groebnerMatrix(35,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(35,6); groebnerMatrix(35,6) = 0.0; groebnerMatrix(35,18) = groebnerMatrix(35,18) - factor * groebnerMatrix(13,156); groebnerMatrix(35,35) = groebnerMatrix(35,35) - factor * groebnerMatrix(13,162); groebnerMatrix(35,189) = groebnerMatrix(35,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(35,10); groebnerMatrix(35,10) = 0.0; groebnerMatrix(35,20) = groebnerMatrix(35,20) - factor * groebnerMatrix(16,158); groebnerMatrix(35,163) = groebnerMatrix(35,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(35,11); groebnerMatrix(35,11) = 0.0; groebnerMatrix(35,21) = groebnerMatrix(35,21) - factor * groebnerMatrix(16,158); groebnerMatrix(35,164) = groebnerMatrix(35,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(35,12); groebnerMatrix(35,12) = 0.0; groebnerMatrix(35,23) = groebnerMatrix(35,23) - factor * groebnerMatrix(16,158); groebnerMatrix(35,165) = groebnerMatrix(35,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(35,13); groebnerMatrix(35,13) = 0.0; groebnerMatrix(35,17) = groebnerMatrix(35,17) - factor * groebnerMatrix(14,153); groebnerMatrix(35,30) = groebnerMatrix(35,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(35,14); groebnerMatrix(35,14) = 0.0; groebnerMatrix(35,16) = groebnerMatrix(35,16) - factor * groebnerMatrix(19,152); groebnerMatrix(35,182) = groebnerMatrix(35,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(35,15); groebnerMatrix(35,15) = 0.0; groebnerMatrix(35,26) = groebnerMatrix(35,26) - factor * groebnerMatrix(16,158); groebnerMatrix(35,166) = groebnerMatrix(35,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(35,18); groebnerMatrix(35,18) = 0.0; groebnerMatrix(35,29) = groebnerMatrix(35,29) - factor * groebnerMatrix(16,158); groebnerMatrix(35,167) = groebnerMatrix(35,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(35,19); groebnerMatrix(35,19) = 0.0; groebnerMatrix(35,21) = groebnerMatrix(35,21) - factor * groebnerMatrix(15,144); groebnerMatrix(35,24) = groebnerMatrix(35,24) - factor * groebnerMatrix(15,147); groebnerMatrix(35,192) = groebnerMatrix(35,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(35,22); groebnerMatrix(35,22) = 0.0; groebnerMatrix(35,36) = groebnerMatrix(35,36) - factor * groebnerMatrix(24,160); groebnerMatrix(35,123) = groebnerMatrix(35,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(35,25); groebnerMatrix(35,25) = 0.0; groebnerMatrix(35,29) = groebnerMatrix(35,29) - factor * groebnerMatrix(14,153); groebnerMatrix(35,35) = groebnerMatrix(35,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(35,26); groebnerMatrix(35,26) = 0.0; groebnerMatrix(35,28) = groebnerMatrix(35,28) - factor * groebnerMatrix(19,152); groebnerMatrix(35,183) = groebnerMatrix(35,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(35,27); groebnerMatrix(35,27) = 0.0; groebnerMatrix(35,33) = groebnerMatrix(35,33) - factor * groebnerMatrix(28,157); groebnerMatrix(35,175) = groebnerMatrix(35,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(35,30); groebnerMatrix(35,30) = 0.0; groebnerMatrix(35,34) = groebnerMatrix(35,34) - factor * groebnerMatrix(16,158); groebnerMatrix(35,168) = groebnerMatrix(35,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(35,39); groebnerMatrix(35,39) = 0.0; groebnerMatrix(35,63) = groebnerMatrix(35,63) - factor * groebnerMatrix(12,171); groebnerMatrix(35,101) = groebnerMatrix(35,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,40); groebnerMatrix(35,40) = 0.0; groebnerMatrix(35,62) = groebnerMatrix(35,62) - factor * groebnerMatrix(20,170); groebnerMatrix(35,158) = groebnerMatrix(35,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(35,41); groebnerMatrix(35,41) = 0.0; groebnerMatrix(35,65) = groebnerMatrix(35,65) - factor * groebnerMatrix(12,171); groebnerMatrix(35,102) = groebnerMatrix(35,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,42); groebnerMatrix(35,42) = 0.0; groebnerMatrix(35,64) = groebnerMatrix(35,64) - factor * groebnerMatrix(20,170); groebnerMatrix(35,159) = groebnerMatrix(35,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(35,43); groebnerMatrix(35,43) = 0.0; groebnerMatrix(35,56) = groebnerMatrix(35,56) - factor * groebnerMatrix(22,162); groebnerMatrix(35,139) = groebnerMatrix(35,139) - factor * groebnerMatrix(22,186); groebnerMatrix(35,193) = groebnerMatrix(35,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(35,44); groebnerMatrix(35,44) = 0.0; groebnerMatrix(35,72) = groebnerMatrix(35,72) - factor * groebnerMatrix(11,174); groebnerMatrix(35,113) = groebnerMatrix(35,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(35,45); groebnerMatrix(35,45) = 0.0; groebnerMatrix(35,73) = groebnerMatrix(35,73) - factor * groebnerMatrix(11,174); groebnerMatrix(35,114) = groebnerMatrix(35,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(35,46); groebnerMatrix(35,46) = 0.0; groebnerMatrix(35,72) = groebnerMatrix(35,72) - factor * groebnerMatrix(12,171); groebnerMatrix(35,109) = groebnerMatrix(35,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,47); groebnerMatrix(35,47) = 0.0; groebnerMatrix(35,71) = groebnerMatrix(35,71) - factor * groebnerMatrix(20,170); groebnerMatrix(35,161) = groebnerMatrix(35,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(35,48); groebnerMatrix(35,48) = 0.0; groebnerMatrix(35,52) = groebnerMatrix(35,52) - factor * groebnerMatrix(16,158); groebnerMatrix(35,169) = groebnerMatrix(35,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(35,49); groebnerMatrix(35,49) = 0.0; groebnerMatrix(35,75) = groebnerMatrix(35,75) - factor * groebnerMatrix(11,174); groebnerMatrix(35,116) = groebnerMatrix(35,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(35,50); groebnerMatrix(35,50) = 0.0; groebnerMatrix(35,74) = groebnerMatrix(35,74) - factor * groebnerMatrix(21,173); groebnerMatrix(35,154) = groebnerMatrix(35,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(35,51); groebnerMatrix(35,51) = 0.0; groebnerMatrix(35,77) = groebnerMatrix(35,77) - factor * groebnerMatrix(12,171); groebnerMatrix(35,114) = groebnerMatrix(35,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,52); groebnerMatrix(35,52) = 0.0; groebnerMatrix(35,76) = groebnerMatrix(35,76) - factor * groebnerMatrix(20,170); groebnerMatrix(35,162) = groebnerMatrix(35,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(35,53); groebnerMatrix(35,53) = 0.0; groebnerMatrix(35,105) = groebnerMatrix(35,105) - factor * groebnerMatrix(27,181); groebnerMatrix(35,146) = groebnerMatrix(35,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(35,54); groebnerMatrix(35,54) = 0.0; groebnerMatrix(35,80) = groebnerMatrix(35,80) - factor * groebnerMatrix(11,174); groebnerMatrix(35,117) = groebnerMatrix(35,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(35,55); groebnerMatrix(35,55) = 0.0; groebnerMatrix(35,79) = groebnerMatrix(35,79) - factor * groebnerMatrix(21,173); groebnerMatrix(35,159) = groebnerMatrix(35,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(35,56); groebnerMatrix(35,56) = 0.0; groebnerMatrix(35,115) = groebnerMatrix(35,115) - factor * groebnerMatrix(27,181); groebnerMatrix(35,158) = groebnerMatrix(35,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(35,57); groebnerMatrix(35,57) = 0.0; groebnerMatrix(35,90) = groebnerMatrix(35,90) - factor * groebnerMatrix(10,177); groebnerMatrix(35,134) = groebnerMatrix(35,134) - factor * groebnerMatrix(10,186); groebnerMatrix(35,188) = groebnerMatrix(35,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(35,58); groebnerMatrix(35,58) = 0.0; groebnerMatrix(35,91) = groebnerMatrix(35,91) - factor * groebnerMatrix(10,177); groebnerMatrix(35,135) = groebnerMatrix(35,135) - factor * groebnerMatrix(10,186); groebnerMatrix(35,189) = groebnerMatrix(35,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(35,59); groebnerMatrix(35,59) = 0.0; groebnerMatrix(35,93) = groebnerMatrix(35,93) - factor * groebnerMatrix(10,177); groebnerMatrix(35,137) = groebnerMatrix(35,137) - factor * groebnerMatrix(10,186); groebnerMatrix(35,191) = groebnerMatrix(35,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(35,60); groebnerMatrix(35,60) = 0.0; groebnerMatrix(35,94) = groebnerMatrix(35,94) - factor * groebnerMatrix(10,177); groebnerMatrix(35,138) = groebnerMatrix(35,138) - factor * groebnerMatrix(10,186); groebnerMatrix(35,192) = groebnerMatrix(35,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(35,61); groebnerMatrix(35,61) = 0.0; groebnerMatrix(35,63) = groebnerMatrix(35,63) - factor * groebnerMatrix(15,144); groebnerMatrix(35,66) = groebnerMatrix(35,66) - factor * groebnerMatrix(15,147); groebnerMatrix(35,194) = groebnerMatrix(35,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(35,64); groebnerMatrix(35,64) = 0.0; groebnerMatrix(35,98) = groebnerMatrix(35,98) - factor * groebnerMatrix(17,179); groebnerMatrix(35,148) = groebnerMatrix(35,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(35,65); groebnerMatrix(35,65) = 0.0; groebnerMatrix(35,99) = groebnerMatrix(35,99) - factor * groebnerMatrix(17,179); groebnerMatrix(35,149) = groebnerMatrix(35,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(35,66); groebnerMatrix(35,66) = 0.0; groebnerMatrix(35,101) = groebnerMatrix(35,101) - factor * groebnerMatrix(17,179); groebnerMatrix(35,150) = groebnerMatrix(35,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(35,67); groebnerMatrix(35,67) = 0.0; groebnerMatrix(35,72) = groebnerMatrix(35,72) - factor * groebnerMatrix(14,153); groebnerMatrix(35,78) = groebnerMatrix(35,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(35,68); groebnerMatrix(35,68) = 0.0; groebnerMatrix(35,71) = groebnerMatrix(35,71) - factor * groebnerMatrix(19,152); groebnerMatrix(35,185) = groebnerMatrix(35,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(35,69); groebnerMatrix(35,69) = 0.0; groebnerMatrix(35,104) = groebnerMatrix(35,104) - factor * groebnerMatrix(17,179); groebnerMatrix(35,151) = groebnerMatrix(35,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(35,70); groebnerMatrix(35,70) = 0.0; groebnerMatrix(35,75) = groebnerMatrix(35,75) - factor * groebnerMatrix(13,156); groebnerMatrix(35,81) = groebnerMatrix(35,81) - factor * groebnerMatrix(13,162); groebnerMatrix(35,194) = groebnerMatrix(35,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(35,73); groebnerMatrix(35,73) = 0.0; groebnerMatrix(35,77) = groebnerMatrix(35,77) - factor * groebnerMatrix(16,158); groebnerMatrix(35,176) = groebnerMatrix(35,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(35,76); groebnerMatrix(35,76) = 0.0; groebnerMatrix(35,107) = groebnerMatrix(35,107) - factor * groebnerMatrix(18,182); groebnerMatrix(35,142) = groebnerMatrix(35,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(35,77); groebnerMatrix(35,77) = 0.0; groebnerMatrix(35,108) = groebnerMatrix(35,108) - factor * groebnerMatrix(18,182); groebnerMatrix(35,143) = groebnerMatrix(35,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(35,78); groebnerMatrix(35,78) = 0.0; groebnerMatrix(35,113) = groebnerMatrix(35,113) - factor * groebnerMatrix(17,179); groebnerMatrix(35,160) = groebnerMatrix(35,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(35,79); groebnerMatrix(35,79) = 0.0; groebnerMatrix(35,110) = groebnerMatrix(35,110) - factor * groebnerMatrix(18,182); groebnerMatrix(35,148) = groebnerMatrix(35,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(35,80); groebnerMatrix(35,80) = 0.0; groebnerMatrix(35,111) = groebnerMatrix(35,111) - factor * groebnerMatrix(18,182); groebnerMatrix(35,152) = groebnerMatrix(35,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(35,81); groebnerMatrix(35,81) = 0.0; groebnerMatrix(35,116) = groebnerMatrix(35,116) - factor * groebnerMatrix(18,182); groebnerMatrix(35,157) = groebnerMatrix(35,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(35,82); groebnerMatrix(35,82) = 0.0; groebnerMatrix(35,90) = groebnerMatrix(35,90) - factor * groebnerMatrix(12,171); groebnerMatrix(35,127) = groebnerMatrix(35,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,83); groebnerMatrix(35,83) = 0.0; groebnerMatrix(35,89) = groebnerMatrix(35,89) - factor * groebnerMatrix(20,170); groebnerMatrix(35,175) = groebnerMatrix(35,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(35,84); groebnerMatrix(35,84) = 0.0; groebnerMatrix(35,119) = groebnerMatrix(35,119) - factor * groebnerMatrix(17,179); groebnerMatrix(35,166) = groebnerMatrix(35,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(35,85); groebnerMatrix(35,85) = 0.0; groebnerMatrix(35,93) = groebnerMatrix(35,93) - factor * groebnerMatrix(11,174); groebnerMatrix(35,130) = groebnerMatrix(35,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(35,86); groebnerMatrix(35,86) = 0.0; groebnerMatrix(35,92) = groebnerMatrix(35,92) - factor * groebnerMatrix(21,173); groebnerMatrix(35,172) = groebnerMatrix(35,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(35,87); groebnerMatrix(35,87) = 0.0; groebnerMatrix(35,122) = groebnerMatrix(35,122) - factor * groebnerMatrix(18,182); groebnerMatrix(35,163) = groebnerMatrix(35,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(35,91); groebnerMatrix(35,91) = 0.0; groebnerMatrix(35,126) = groebnerMatrix(35,126) - factor * groebnerMatrix(17,179); groebnerMatrix(35,173) = groebnerMatrix(35,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(35,94); groebnerMatrix(35,94) = 0.0; groebnerMatrix(35,129) = groebnerMatrix(35,129) - factor * groebnerMatrix(18,182); groebnerMatrix(35,170) = groebnerMatrix(35,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(35,97); groebnerMatrix(35,97) = 0.0; groebnerMatrix(35,99) = groebnerMatrix(35,99) - factor * groebnerMatrix(15,144); groebnerMatrix(35,102) = groebnerMatrix(35,102) - factor * groebnerMatrix(15,147); groebnerMatrix(35,195) = groebnerMatrix(35,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(35,100); groebnerMatrix(35,100) = 0.0; groebnerMatrix(35,115) = groebnerMatrix(35,115) - factor * groebnerMatrix(24,160); groebnerMatrix(35,139) = groebnerMatrix(35,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(35,103); groebnerMatrix(35,103) = 0.0; groebnerMatrix(35,108) = groebnerMatrix(35,108) - factor * groebnerMatrix(14,153); groebnerMatrix(35,114) = groebnerMatrix(35,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(35,104); groebnerMatrix(35,104) = 0.0; groebnerMatrix(35,107) = groebnerMatrix(35,107) - factor * groebnerMatrix(19,152); groebnerMatrix(35,186) = groebnerMatrix(35,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(35,105); groebnerMatrix(35,105) = 0.0; groebnerMatrix(35,112) = groebnerMatrix(35,112) - factor * groebnerMatrix(28,157); groebnerMatrix(35,185) = groebnerMatrix(35,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(35,106); groebnerMatrix(35,106) = 0.0; groebnerMatrix(35,111) = groebnerMatrix(35,111) - factor * groebnerMatrix(13,156); groebnerMatrix(35,117) = groebnerMatrix(35,117) - factor * groebnerMatrix(13,162); groebnerMatrix(35,195) = groebnerMatrix(35,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(35,109); groebnerMatrix(35,109) = 0.0; groebnerMatrix(35,113) = groebnerMatrix(35,113) - factor * groebnerMatrix(16,158); groebnerMatrix(35,184) = groebnerMatrix(35,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(35,118); groebnerMatrix(35,118) = 0.0; groebnerMatrix(35,126) = groebnerMatrix(35,126) - factor * groebnerMatrix(12,171); groebnerMatrix(35,135) = groebnerMatrix(35,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,119); groebnerMatrix(35,119) = 0.0; groebnerMatrix(35,125) = groebnerMatrix(35,125) - factor * groebnerMatrix(20,170); groebnerMatrix(35,183) = groebnerMatrix(35,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(35,120); groebnerMatrix(35,120) = 0.0; groebnerMatrix(35,133) = groebnerMatrix(35,133) - factor * groebnerMatrix(29,178); groebnerMatrix(35,182) = groebnerMatrix(35,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(35,121); groebnerMatrix(35,121) = 0.0; groebnerMatrix(35,129) = groebnerMatrix(35,129) - factor * groebnerMatrix(11,174); groebnerMatrix(35,138) = groebnerMatrix(35,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(35,122); groebnerMatrix(35,122) = 0.0; groebnerMatrix(35,128) = groebnerMatrix(35,128) - factor * groebnerMatrix(21,173); groebnerMatrix(35,180) = groebnerMatrix(35,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(35,123); groebnerMatrix(35,123) = 0.0; groebnerMatrix(35,136) = groebnerMatrix(35,136) - factor * groebnerMatrix(27,181); groebnerMatrix(35,179) = groebnerMatrix(35,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(35,127); groebnerMatrix(35,127) = 0.0; groebnerMatrix(35,134) = groebnerMatrix(35,134) - factor * groebnerMatrix(17,179); groebnerMatrix(35,181) = groebnerMatrix(35,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(35,130); groebnerMatrix(35,130) = 0.0; groebnerMatrix(35,137) = groebnerMatrix(35,137) - factor * groebnerMatrix(18,182); groebnerMatrix(35,178) = groebnerMatrix(35,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(35,142); groebnerMatrix(35,142) = 0.0; groebnerMatrix(35,144) = groebnerMatrix(35,144) - factor * groebnerMatrix(15,144); groebnerMatrix(35,147) = groebnerMatrix(35,147) - factor * groebnerMatrix(15,147); groebnerMatrix(35,196) = groebnerMatrix(35,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(35,143); groebnerMatrix(35,143) = 0.0; groebnerMatrix(35,155) = groebnerMatrix(35,155) - factor * groebnerMatrix(26,155); groebnerMatrix(35,176) = groebnerMatrix(35,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(35,144); groebnerMatrix(35,144) = 0.0; groebnerMatrix(35,156) = groebnerMatrix(35,156) - factor * groebnerMatrix(25,156); groebnerMatrix(35,177) = groebnerMatrix(35,177) - factor * groebnerMatrix(25,177); groebnerMatrix(35,196) = groebnerMatrix(35,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(35,146); groebnerMatrix(35,146) = 0.0; groebnerMatrix(35,161) = groebnerMatrix(35,161) - factor * groebnerMatrix(23,161); groebnerMatrix(35,185) = groebnerMatrix(35,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(35,147); groebnerMatrix(35,147) = 0.0; groebnerMatrix(35,162) = groebnerMatrix(35,162) - factor * groebnerMatrix(22,162); groebnerMatrix(35,186) = groebnerMatrix(35,186) - factor * groebnerMatrix(22,186); groebnerMatrix(35,196) = groebnerMatrix(35,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(35,148); groebnerMatrix(35,148) = 0.0; groebnerMatrix(35,153) = groebnerMatrix(35,153) - factor * groebnerMatrix(14,153); groebnerMatrix(35,159) = groebnerMatrix(35,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(35,149); groebnerMatrix(35,149) = 0.0; groebnerMatrix(35,152) = groebnerMatrix(35,152) - factor * groebnerMatrix(19,152); groebnerMatrix(35,195) = groebnerMatrix(35,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(35,150); groebnerMatrix(35,150) = 0.0; groebnerMatrix(35,157) = groebnerMatrix(35,157) - factor * groebnerMatrix(28,157); groebnerMatrix(35,194) = groebnerMatrix(35,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(35,151); groebnerMatrix(35,151) = 0.0; groebnerMatrix(35,156) = groebnerMatrix(35,156) - factor * groebnerMatrix(13,156); groebnerMatrix(35,162) = groebnerMatrix(35,162) - factor * groebnerMatrix(13,162); groebnerMatrix(35,196) = groebnerMatrix(35,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,35); groebnerRow31_000000000_f(groebnerMatrix,35); factor = -groebnerMatrix(35,154); groebnerMatrix(35,154) = 0.0; groebnerMatrix(35,158) = groebnerMatrix(35,158) - factor * groebnerMatrix(16,158); groebnerMatrix(35,193) = groebnerMatrix(35,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,35); groebnerRow33_000000000_f(groebnerMatrix,35); groebnerRow34_000000000_f(groebnerMatrix,35); factor = groebnerMatrix(35,163); groebnerMatrix(35,163) = 0.0; groebnerMatrix(35,171) = groebnerMatrix(35,171) - factor * groebnerMatrix(12,171); groebnerMatrix(35,180) = groebnerMatrix(35,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(35,164); groebnerMatrix(35,164) = 0.0; groebnerMatrix(35,170) = groebnerMatrix(35,170) - factor * groebnerMatrix(20,170); groebnerMatrix(35,192) = groebnerMatrix(35,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(35,165); groebnerMatrix(35,165) = 0.0; groebnerMatrix(35,178) = groebnerMatrix(35,178) - factor * groebnerMatrix(29,178); groebnerMatrix(35,191) = groebnerMatrix(35,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(35,166); groebnerMatrix(35,166) = 0.0; groebnerMatrix(35,174) = groebnerMatrix(35,174) - factor * groebnerMatrix(11,174); groebnerMatrix(35,183) = groebnerMatrix(35,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(35,167); groebnerMatrix(35,167) = 0.0; groebnerMatrix(35,173) = groebnerMatrix(35,173) - factor * groebnerMatrix(21,173); groebnerMatrix(35,189) = groebnerMatrix(35,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(35,168); groebnerMatrix(35,168) = 0.0; groebnerMatrix(35,181) = groebnerMatrix(35,181) - factor * groebnerMatrix(27,181); groebnerMatrix(35,188) = groebnerMatrix(35,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(35,169); groebnerMatrix(35,169) = 0.0; groebnerMatrix(35,177) = groebnerMatrix(35,177) - factor * groebnerMatrix(10,177); groebnerMatrix(35,186) = groebnerMatrix(35,186) - factor * groebnerMatrix(10,186); groebnerMatrix(35,196) = groebnerMatrix(35,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(35,172); groebnerMatrix(35,172) = 0.0; groebnerMatrix(35,179) = groebnerMatrix(35,179) - factor * groebnerMatrix(17,179); groebnerMatrix(35,190) = groebnerMatrix(35,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(35,175); groebnerMatrix(35,175) = 0.0; groebnerMatrix(35,182) = groebnerMatrix(35,182) - factor * groebnerMatrix(18,182); groebnerMatrix(35,187) = groebnerMatrix(35,187) - factor * groebnerMatrix(18,187); sPolynomial36(groebnerMatrix); factor = -groebnerMatrix(36,1); groebnerMatrix(36,1) = 0.0; groebnerMatrix(36,8) = groebnerMatrix(36,8) - factor * groebnerMatrix(19,152); groebnerMatrix(36,179) = groebnerMatrix(36,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(36,2); groebnerMatrix(36,2) = 0.0; groebnerMatrix(36,11) = groebnerMatrix(36,11) - factor * groebnerMatrix(14,153); groebnerMatrix(36,24) = groebnerMatrix(36,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(36,3); groebnerMatrix(36,3) = 0.0; groebnerMatrix(36,10) = groebnerMatrix(36,10) - factor * groebnerMatrix(19,152); groebnerMatrix(36,180) = groebnerMatrix(36,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(36,4); groebnerMatrix(36,4) = 0.0; groebnerMatrix(36,36) = groebnerMatrix(36,36) - factor * groebnerMatrix(22,162); groebnerMatrix(36,136) = groebnerMatrix(36,136) - factor * groebnerMatrix(22,186); groebnerMatrix(36,190) = groebnerMatrix(36,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(36,5); groebnerMatrix(36,5) = 0.0; groebnerMatrix(36,17) = groebnerMatrix(36,17) - factor * groebnerMatrix(13,156); groebnerMatrix(36,34) = groebnerMatrix(36,34) - factor * groebnerMatrix(13,162); groebnerMatrix(36,188) = groebnerMatrix(36,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(36,6); groebnerMatrix(36,6) = 0.0; groebnerMatrix(36,18) = groebnerMatrix(36,18) - factor * groebnerMatrix(13,156); groebnerMatrix(36,35) = groebnerMatrix(36,35) - factor * groebnerMatrix(13,162); groebnerMatrix(36,189) = groebnerMatrix(36,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(36,10); groebnerMatrix(36,10) = 0.0; groebnerMatrix(36,20) = groebnerMatrix(36,20) - factor * groebnerMatrix(16,158); groebnerMatrix(36,163) = groebnerMatrix(36,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(36,11); groebnerMatrix(36,11) = 0.0; groebnerMatrix(36,21) = groebnerMatrix(36,21) - factor * groebnerMatrix(16,158); groebnerMatrix(36,164) = groebnerMatrix(36,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(36,12); groebnerMatrix(36,12) = 0.0; groebnerMatrix(36,23) = groebnerMatrix(36,23) - factor * groebnerMatrix(16,158); groebnerMatrix(36,165) = groebnerMatrix(36,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(36,13); groebnerMatrix(36,13) = 0.0; groebnerMatrix(36,17) = groebnerMatrix(36,17) - factor * groebnerMatrix(14,153); groebnerMatrix(36,30) = groebnerMatrix(36,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(36,14); groebnerMatrix(36,14) = 0.0; groebnerMatrix(36,16) = groebnerMatrix(36,16) - factor * groebnerMatrix(19,152); groebnerMatrix(36,182) = groebnerMatrix(36,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(36,15); groebnerMatrix(36,15) = 0.0; groebnerMatrix(36,26) = groebnerMatrix(36,26) - factor * groebnerMatrix(16,158); groebnerMatrix(36,166) = groebnerMatrix(36,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(36,18); groebnerMatrix(36,18) = 0.0; groebnerMatrix(36,29) = groebnerMatrix(36,29) - factor * groebnerMatrix(16,158); groebnerMatrix(36,167) = groebnerMatrix(36,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(36,19); groebnerMatrix(36,19) = 0.0; groebnerMatrix(36,21) = groebnerMatrix(36,21) - factor * groebnerMatrix(15,144); groebnerMatrix(36,24) = groebnerMatrix(36,24) - factor * groebnerMatrix(15,147); groebnerMatrix(36,192) = groebnerMatrix(36,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(36,22); groebnerMatrix(36,22) = 0.0; groebnerMatrix(36,36) = groebnerMatrix(36,36) - factor * groebnerMatrix(24,160); groebnerMatrix(36,123) = groebnerMatrix(36,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(36,25); groebnerMatrix(36,25) = 0.0; groebnerMatrix(36,29) = groebnerMatrix(36,29) - factor * groebnerMatrix(14,153); groebnerMatrix(36,35) = groebnerMatrix(36,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(36,26); groebnerMatrix(36,26) = 0.0; groebnerMatrix(36,28) = groebnerMatrix(36,28) - factor * groebnerMatrix(19,152); groebnerMatrix(36,183) = groebnerMatrix(36,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(36,27); groebnerMatrix(36,27) = 0.0; groebnerMatrix(36,33) = groebnerMatrix(36,33) - factor * groebnerMatrix(28,157); groebnerMatrix(36,175) = groebnerMatrix(36,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(36,30); groebnerMatrix(36,30) = 0.0; groebnerMatrix(36,34) = groebnerMatrix(36,34) - factor * groebnerMatrix(16,158); groebnerMatrix(36,168) = groebnerMatrix(36,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(36,39); groebnerMatrix(36,39) = 0.0; groebnerMatrix(36,63) = groebnerMatrix(36,63) - factor * groebnerMatrix(12,171); groebnerMatrix(36,101) = groebnerMatrix(36,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,40); groebnerMatrix(36,40) = 0.0; groebnerMatrix(36,62) = groebnerMatrix(36,62) - factor * groebnerMatrix(20,170); groebnerMatrix(36,158) = groebnerMatrix(36,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(36,41); groebnerMatrix(36,41) = 0.0; groebnerMatrix(36,65) = groebnerMatrix(36,65) - factor * groebnerMatrix(12,171); groebnerMatrix(36,102) = groebnerMatrix(36,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,42); groebnerMatrix(36,42) = 0.0; groebnerMatrix(36,64) = groebnerMatrix(36,64) - factor * groebnerMatrix(20,170); groebnerMatrix(36,159) = groebnerMatrix(36,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(36,43); groebnerMatrix(36,43) = 0.0; groebnerMatrix(36,56) = groebnerMatrix(36,56) - factor * groebnerMatrix(22,162); groebnerMatrix(36,139) = groebnerMatrix(36,139) - factor * groebnerMatrix(22,186); groebnerMatrix(36,193) = groebnerMatrix(36,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(36,44); groebnerMatrix(36,44) = 0.0; groebnerMatrix(36,72) = groebnerMatrix(36,72) - factor * groebnerMatrix(11,174); groebnerMatrix(36,113) = groebnerMatrix(36,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(36,45); groebnerMatrix(36,45) = 0.0; groebnerMatrix(36,73) = groebnerMatrix(36,73) - factor * groebnerMatrix(11,174); groebnerMatrix(36,114) = groebnerMatrix(36,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(36,46); groebnerMatrix(36,46) = 0.0; groebnerMatrix(36,72) = groebnerMatrix(36,72) - factor * groebnerMatrix(12,171); groebnerMatrix(36,109) = groebnerMatrix(36,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,47); groebnerMatrix(36,47) = 0.0; groebnerMatrix(36,71) = groebnerMatrix(36,71) - factor * groebnerMatrix(20,170); groebnerMatrix(36,161) = groebnerMatrix(36,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(36,48); groebnerMatrix(36,48) = 0.0; groebnerMatrix(36,52) = groebnerMatrix(36,52) - factor * groebnerMatrix(16,158); groebnerMatrix(36,169) = groebnerMatrix(36,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(36,49); groebnerMatrix(36,49) = 0.0; groebnerMatrix(36,75) = groebnerMatrix(36,75) - factor * groebnerMatrix(11,174); groebnerMatrix(36,116) = groebnerMatrix(36,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(36,50); groebnerMatrix(36,50) = 0.0; groebnerMatrix(36,74) = groebnerMatrix(36,74) - factor * groebnerMatrix(21,173); groebnerMatrix(36,154) = groebnerMatrix(36,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(36,51); groebnerMatrix(36,51) = 0.0; groebnerMatrix(36,77) = groebnerMatrix(36,77) - factor * groebnerMatrix(12,171); groebnerMatrix(36,114) = groebnerMatrix(36,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,52); groebnerMatrix(36,52) = 0.0; groebnerMatrix(36,76) = groebnerMatrix(36,76) - factor * groebnerMatrix(20,170); groebnerMatrix(36,162) = groebnerMatrix(36,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(36,53); groebnerMatrix(36,53) = 0.0; groebnerMatrix(36,105) = groebnerMatrix(36,105) - factor * groebnerMatrix(27,181); groebnerMatrix(36,146) = groebnerMatrix(36,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(36,54); groebnerMatrix(36,54) = 0.0; groebnerMatrix(36,80) = groebnerMatrix(36,80) - factor * groebnerMatrix(11,174); groebnerMatrix(36,117) = groebnerMatrix(36,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(36,55); groebnerMatrix(36,55) = 0.0; groebnerMatrix(36,79) = groebnerMatrix(36,79) - factor * groebnerMatrix(21,173); groebnerMatrix(36,159) = groebnerMatrix(36,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(36,56); groebnerMatrix(36,56) = 0.0; groebnerMatrix(36,115) = groebnerMatrix(36,115) - factor * groebnerMatrix(27,181); groebnerMatrix(36,158) = groebnerMatrix(36,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(36,57); groebnerMatrix(36,57) = 0.0; groebnerMatrix(36,90) = groebnerMatrix(36,90) - factor * groebnerMatrix(10,177); groebnerMatrix(36,134) = groebnerMatrix(36,134) - factor * groebnerMatrix(10,186); groebnerMatrix(36,188) = groebnerMatrix(36,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(36,58); groebnerMatrix(36,58) = 0.0; groebnerMatrix(36,91) = groebnerMatrix(36,91) - factor * groebnerMatrix(10,177); groebnerMatrix(36,135) = groebnerMatrix(36,135) - factor * groebnerMatrix(10,186); groebnerMatrix(36,189) = groebnerMatrix(36,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(36,59); groebnerMatrix(36,59) = 0.0; groebnerMatrix(36,93) = groebnerMatrix(36,93) - factor * groebnerMatrix(10,177); groebnerMatrix(36,137) = groebnerMatrix(36,137) - factor * groebnerMatrix(10,186); groebnerMatrix(36,191) = groebnerMatrix(36,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(36,60); groebnerMatrix(36,60) = 0.0; groebnerMatrix(36,94) = groebnerMatrix(36,94) - factor * groebnerMatrix(10,177); groebnerMatrix(36,138) = groebnerMatrix(36,138) - factor * groebnerMatrix(10,186); groebnerMatrix(36,192) = groebnerMatrix(36,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(36,61); groebnerMatrix(36,61) = 0.0; groebnerMatrix(36,63) = groebnerMatrix(36,63) - factor * groebnerMatrix(15,144); groebnerMatrix(36,66) = groebnerMatrix(36,66) - factor * groebnerMatrix(15,147); groebnerMatrix(36,194) = groebnerMatrix(36,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(36,64); groebnerMatrix(36,64) = 0.0; groebnerMatrix(36,98) = groebnerMatrix(36,98) - factor * groebnerMatrix(17,179); groebnerMatrix(36,148) = groebnerMatrix(36,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(36,65); groebnerMatrix(36,65) = 0.0; groebnerMatrix(36,99) = groebnerMatrix(36,99) - factor * groebnerMatrix(17,179); groebnerMatrix(36,149) = groebnerMatrix(36,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(36,66); groebnerMatrix(36,66) = 0.0; groebnerMatrix(36,101) = groebnerMatrix(36,101) - factor * groebnerMatrix(17,179); groebnerMatrix(36,150) = groebnerMatrix(36,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(36,67); groebnerMatrix(36,67) = 0.0; groebnerMatrix(36,72) = groebnerMatrix(36,72) - factor * groebnerMatrix(14,153); groebnerMatrix(36,78) = groebnerMatrix(36,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(36,68); groebnerMatrix(36,68) = 0.0; groebnerMatrix(36,71) = groebnerMatrix(36,71) - factor * groebnerMatrix(19,152); groebnerMatrix(36,185) = groebnerMatrix(36,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(36,69); groebnerMatrix(36,69) = 0.0; groebnerMatrix(36,104) = groebnerMatrix(36,104) - factor * groebnerMatrix(17,179); groebnerMatrix(36,151) = groebnerMatrix(36,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(36,70); groebnerMatrix(36,70) = 0.0; groebnerMatrix(36,75) = groebnerMatrix(36,75) - factor * groebnerMatrix(13,156); groebnerMatrix(36,81) = groebnerMatrix(36,81) - factor * groebnerMatrix(13,162); groebnerMatrix(36,194) = groebnerMatrix(36,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(36,73); groebnerMatrix(36,73) = 0.0; groebnerMatrix(36,77) = groebnerMatrix(36,77) - factor * groebnerMatrix(16,158); groebnerMatrix(36,176) = groebnerMatrix(36,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(36,76); groebnerMatrix(36,76) = 0.0; groebnerMatrix(36,107) = groebnerMatrix(36,107) - factor * groebnerMatrix(18,182); groebnerMatrix(36,142) = groebnerMatrix(36,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(36,77); groebnerMatrix(36,77) = 0.0; groebnerMatrix(36,108) = groebnerMatrix(36,108) - factor * groebnerMatrix(18,182); groebnerMatrix(36,143) = groebnerMatrix(36,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(36,78); groebnerMatrix(36,78) = 0.0; groebnerMatrix(36,113) = groebnerMatrix(36,113) - factor * groebnerMatrix(17,179); groebnerMatrix(36,160) = groebnerMatrix(36,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(36,79); groebnerMatrix(36,79) = 0.0; groebnerMatrix(36,110) = groebnerMatrix(36,110) - factor * groebnerMatrix(18,182); groebnerMatrix(36,148) = groebnerMatrix(36,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(36,80); groebnerMatrix(36,80) = 0.0; groebnerMatrix(36,111) = groebnerMatrix(36,111) - factor * groebnerMatrix(18,182); groebnerMatrix(36,152) = groebnerMatrix(36,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(36,81); groebnerMatrix(36,81) = 0.0; groebnerMatrix(36,116) = groebnerMatrix(36,116) - factor * groebnerMatrix(18,182); groebnerMatrix(36,157) = groebnerMatrix(36,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(36,82); groebnerMatrix(36,82) = 0.0; groebnerMatrix(36,90) = groebnerMatrix(36,90) - factor * groebnerMatrix(12,171); groebnerMatrix(36,127) = groebnerMatrix(36,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,83); groebnerMatrix(36,83) = 0.0; groebnerMatrix(36,89) = groebnerMatrix(36,89) - factor * groebnerMatrix(20,170); groebnerMatrix(36,175) = groebnerMatrix(36,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(36,84); groebnerMatrix(36,84) = 0.0; groebnerMatrix(36,119) = groebnerMatrix(36,119) - factor * groebnerMatrix(17,179); groebnerMatrix(36,166) = groebnerMatrix(36,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(36,85); groebnerMatrix(36,85) = 0.0; groebnerMatrix(36,93) = groebnerMatrix(36,93) - factor * groebnerMatrix(11,174); groebnerMatrix(36,130) = groebnerMatrix(36,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(36,86); groebnerMatrix(36,86) = 0.0; groebnerMatrix(36,92) = groebnerMatrix(36,92) - factor * groebnerMatrix(21,173); groebnerMatrix(36,172) = groebnerMatrix(36,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(36,87); groebnerMatrix(36,87) = 0.0; groebnerMatrix(36,122) = groebnerMatrix(36,122) - factor * groebnerMatrix(18,182); groebnerMatrix(36,163) = groebnerMatrix(36,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(36,91); groebnerMatrix(36,91) = 0.0; groebnerMatrix(36,126) = groebnerMatrix(36,126) - factor * groebnerMatrix(17,179); groebnerMatrix(36,173) = groebnerMatrix(36,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(36,94); groebnerMatrix(36,94) = 0.0; groebnerMatrix(36,129) = groebnerMatrix(36,129) - factor * groebnerMatrix(18,182); groebnerMatrix(36,170) = groebnerMatrix(36,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(36,97); groebnerMatrix(36,97) = 0.0; groebnerMatrix(36,99) = groebnerMatrix(36,99) - factor * groebnerMatrix(15,144); groebnerMatrix(36,102) = groebnerMatrix(36,102) - factor * groebnerMatrix(15,147); groebnerMatrix(36,195) = groebnerMatrix(36,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(36,100); groebnerMatrix(36,100) = 0.0; groebnerMatrix(36,115) = groebnerMatrix(36,115) - factor * groebnerMatrix(24,160); groebnerMatrix(36,139) = groebnerMatrix(36,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(36,103); groebnerMatrix(36,103) = 0.0; groebnerMatrix(36,108) = groebnerMatrix(36,108) - factor * groebnerMatrix(14,153); groebnerMatrix(36,114) = groebnerMatrix(36,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(36,104); groebnerMatrix(36,104) = 0.0; groebnerMatrix(36,107) = groebnerMatrix(36,107) - factor * groebnerMatrix(19,152); groebnerMatrix(36,186) = groebnerMatrix(36,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(36,105); groebnerMatrix(36,105) = 0.0; groebnerMatrix(36,112) = groebnerMatrix(36,112) - factor * groebnerMatrix(28,157); groebnerMatrix(36,185) = groebnerMatrix(36,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(36,106); groebnerMatrix(36,106) = 0.0; groebnerMatrix(36,111) = groebnerMatrix(36,111) - factor * groebnerMatrix(13,156); groebnerMatrix(36,117) = groebnerMatrix(36,117) - factor * groebnerMatrix(13,162); groebnerMatrix(36,195) = groebnerMatrix(36,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(36,109); groebnerMatrix(36,109) = 0.0; groebnerMatrix(36,113) = groebnerMatrix(36,113) - factor * groebnerMatrix(16,158); groebnerMatrix(36,184) = groebnerMatrix(36,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(36,118); groebnerMatrix(36,118) = 0.0; groebnerMatrix(36,126) = groebnerMatrix(36,126) - factor * groebnerMatrix(12,171); groebnerMatrix(36,135) = groebnerMatrix(36,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,119); groebnerMatrix(36,119) = 0.0; groebnerMatrix(36,125) = groebnerMatrix(36,125) - factor * groebnerMatrix(20,170); groebnerMatrix(36,183) = groebnerMatrix(36,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(36,120); groebnerMatrix(36,120) = 0.0; groebnerMatrix(36,133) = groebnerMatrix(36,133) - factor * groebnerMatrix(29,178); groebnerMatrix(36,182) = groebnerMatrix(36,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(36,121); groebnerMatrix(36,121) = 0.0; groebnerMatrix(36,129) = groebnerMatrix(36,129) - factor * groebnerMatrix(11,174); groebnerMatrix(36,138) = groebnerMatrix(36,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(36,122); groebnerMatrix(36,122) = 0.0; groebnerMatrix(36,128) = groebnerMatrix(36,128) - factor * groebnerMatrix(21,173); groebnerMatrix(36,180) = groebnerMatrix(36,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(36,123); groebnerMatrix(36,123) = 0.0; groebnerMatrix(36,136) = groebnerMatrix(36,136) - factor * groebnerMatrix(27,181); groebnerMatrix(36,179) = groebnerMatrix(36,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(36,127); groebnerMatrix(36,127) = 0.0; groebnerMatrix(36,134) = groebnerMatrix(36,134) - factor * groebnerMatrix(17,179); groebnerMatrix(36,181) = groebnerMatrix(36,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(36,130); groebnerMatrix(36,130) = 0.0; groebnerMatrix(36,137) = groebnerMatrix(36,137) - factor * groebnerMatrix(18,182); groebnerMatrix(36,178) = groebnerMatrix(36,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(36,142); groebnerMatrix(36,142) = 0.0; groebnerMatrix(36,144) = groebnerMatrix(36,144) - factor * groebnerMatrix(15,144); groebnerMatrix(36,147) = groebnerMatrix(36,147) - factor * groebnerMatrix(15,147); groebnerMatrix(36,196) = groebnerMatrix(36,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(36,143); groebnerMatrix(36,143) = 0.0; groebnerMatrix(36,155) = groebnerMatrix(36,155) - factor * groebnerMatrix(26,155); groebnerMatrix(36,176) = groebnerMatrix(36,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(36,144); groebnerMatrix(36,144) = 0.0; groebnerMatrix(36,156) = groebnerMatrix(36,156) - factor * groebnerMatrix(25,156); groebnerMatrix(36,177) = groebnerMatrix(36,177) - factor * groebnerMatrix(25,177); groebnerMatrix(36,196) = groebnerMatrix(36,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(36,146); groebnerMatrix(36,146) = 0.0; groebnerMatrix(36,161) = groebnerMatrix(36,161) - factor * groebnerMatrix(23,161); groebnerMatrix(36,185) = groebnerMatrix(36,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(36,147); groebnerMatrix(36,147) = 0.0; groebnerMatrix(36,162) = groebnerMatrix(36,162) - factor * groebnerMatrix(22,162); groebnerMatrix(36,186) = groebnerMatrix(36,186) - factor * groebnerMatrix(22,186); groebnerMatrix(36,196) = groebnerMatrix(36,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(36,148); groebnerMatrix(36,148) = 0.0; groebnerMatrix(36,153) = groebnerMatrix(36,153) - factor * groebnerMatrix(14,153); groebnerMatrix(36,159) = groebnerMatrix(36,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(36,149); groebnerMatrix(36,149) = 0.0; groebnerMatrix(36,152) = groebnerMatrix(36,152) - factor * groebnerMatrix(19,152); groebnerMatrix(36,195) = groebnerMatrix(36,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(36,150); groebnerMatrix(36,150) = 0.0; groebnerMatrix(36,157) = groebnerMatrix(36,157) - factor * groebnerMatrix(28,157); groebnerMatrix(36,194) = groebnerMatrix(36,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(36,151); groebnerMatrix(36,151) = 0.0; groebnerMatrix(36,156) = groebnerMatrix(36,156) - factor * groebnerMatrix(13,156); groebnerMatrix(36,162) = groebnerMatrix(36,162) - factor * groebnerMatrix(13,162); groebnerMatrix(36,196) = groebnerMatrix(36,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,36); groebnerRow31_000000000_f(groebnerMatrix,36); factor = -groebnerMatrix(36,154); groebnerMatrix(36,154) = 0.0; groebnerMatrix(36,158) = groebnerMatrix(36,158) - factor * groebnerMatrix(16,158); groebnerMatrix(36,193) = groebnerMatrix(36,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,36); groebnerRow33_000000000_f(groebnerMatrix,36); groebnerRow34_000000000_f(groebnerMatrix,36); groebnerRow35_000000000_f(groebnerMatrix,36); factor = groebnerMatrix(36,163); groebnerMatrix(36,163) = 0.0; groebnerMatrix(36,171) = groebnerMatrix(36,171) - factor * groebnerMatrix(12,171); groebnerMatrix(36,180) = groebnerMatrix(36,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(36,164); groebnerMatrix(36,164) = 0.0; groebnerMatrix(36,170) = groebnerMatrix(36,170) - factor * groebnerMatrix(20,170); groebnerMatrix(36,192) = groebnerMatrix(36,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(36,165); groebnerMatrix(36,165) = 0.0; groebnerMatrix(36,178) = groebnerMatrix(36,178) - factor * groebnerMatrix(29,178); groebnerMatrix(36,191) = groebnerMatrix(36,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(36,166); groebnerMatrix(36,166) = 0.0; groebnerMatrix(36,174) = groebnerMatrix(36,174) - factor * groebnerMatrix(11,174); groebnerMatrix(36,183) = groebnerMatrix(36,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(36,167); groebnerMatrix(36,167) = 0.0; groebnerMatrix(36,173) = groebnerMatrix(36,173) - factor * groebnerMatrix(21,173); groebnerMatrix(36,189) = groebnerMatrix(36,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(36,168); groebnerMatrix(36,168) = 0.0; groebnerMatrix(36,181) = groebnerMatrix(36,181) - factor * groebnerMatrix(27,181); groebnerMatrix(36,188) = groebnerMatrix(36,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(36,169); groebnerMatrix(36,169) = 0.0; groebnerMatrix(36,177) = groebnerMatrix(36,177) - factor * groebnerMatrix(10,177); groebnerMatrix(36,186) = groebnerMatrix(36,186) - factor * groebnerMatrix(10,186); groebnerMatrix(36,196) = groebnerMatrix(36,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(36,172); groebnerMatrix(36,172) = 0.0; groebnerMatrix(36,179) = groebnerMatrix(36,179) - factor * groebnerMatrix(17,179); groebnerMatrix(36,190) = groebnerMatrix(36,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(36,175); groebnerMatrix(36,175) = 0.0; groebnerMatrix(36,182) = groebnerMatrix(36,182) - factor * groebnerMatrix(18,182); groebnerMatrix(36,187) = groebnerMatrix(36,187) - factor * groebnerMatrix(18,187); sPolynomial37(groebnerMatrix); factor = -groebnerMatrix(37,1); groebnerMatrix(37,1) = 0.0; groebnerMatrix(37,8) = groebnerMatrix(37,8) - factor * groebnerMatrix(19,152); groebnerMatrix(37,179) = groebnerMatrix(37,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(37,2); groebnerMatrix(37,2) = 0.0; groebnerMatrix(37,11) = groebnerMatrix(37,11) - factor * groebnerMatrix(14,153); groebnerMatrix(37,24) = groebnerMatrix(37,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(37,3); groebnerMatrix(37,3) = 0.0; groebnerMatrix(37,10) = groebnerMatrix(37,10) - factor * groebnerMatrix(19,152); groebnerMatrix(37,180) = groebnerMatrix(37,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(37,4); groebnerMatrix(37,4) = 0.0; groebnerMatrix(37,36) = groebnerMatrix(37,36) - factor * groebnerMatrix(22,162); groebnerMatrix(37,136) = groebnerMatrix(37,136) - factor * groebnerMatrix(22,186); groebnerMatrix(37,190) = groebnerMatrix(37,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(37,5); groebnerMatrix(37,5) = 0.0; groebnerMatrix(37,17) = groebnerMatrix(37,17) - factor * groebnerMatrix(13,156); groebnerMatrix(37,34) = groebnerMatrix(37,34) - factor * groebnerMatrix(13,162); groebnerMatrix(37,188) = groebnerMatrix(37,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(37,6); groebnerMatrix(37,6) = 0.0; groebnerMatrix(37,18) = groebnerMatrix(37,18) - factor * groebnerMatrix(13,156); groebnerMatrix(37,35) = groebnerMatrix(37,35) - factor * groebnerMatrix(13,162); groebnerMatrix(37,189) = groebnerMatrix(37,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(37,10); groebnerMatrix(37,10) = 0.0; groebnerMatrix(37,20) = groebnerMatrix(37,20) - factor * groebnerMatrix(16,158); groebnerMatrix(37,163) = groebnerMatrix(37,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(37,11); groebnerMatrix(37,11) = 0.0; groebnerMatrix(37,21) = groebnerMatrix(37,21) - factor * groebnerMatrix(16,158); groebnerMatrix(37,164) = groebnerMatrix(37,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(37,12); groebnerMatrix(37,12) = 0.0; groebnerMatrix(37,23) = groebnerMatrix(37,23) - factor * groebnerMatrix(16,158); groebnerMatrix(37,165) = groebnerMatrix(37,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(37,13); groebnerMatrix(37,13) = 0.0; groebnerMatrix(37,17) = groebnerMatrix(37,17) - factor * groebnerMatrix(14,153); groebnerMatrix(37,30) = groebnerMatrix(37,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(37,14); groebnerMatrix(37,14) = 0.0; groebnerMatrix(37,16) = groebnerMatrix(37,16) - factor * groebnerMatrix(19,152); groebnerMatrix(37,182) = groebnerMatrix(37,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(37,15); groebnerMatrix(37,15) = 0.0; groebnerMatrix(37,26) = groebnerMatrix(37,26) - factor * groebnerMatrix(16,158); groebnerMatrix(37,166) = groebnerMatrix(37,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(37,18); groebnerMatrix(37,18) = 0.0; groebnerMatrix(37,29) = groebnerMatrix(37,29) - factor * groebnerMatrix(16,158); groebnerMatrix(37,167) = groebnerMatrix(37,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(37,19); groebnerMatrix(37,19) = 0.0; groebnerMatrix(37,21) = groebnerMatrix(37,21) - factor * groebnerMatrix(15,144); groebnerMatrix(37,24) = groebnerMatrix(37,24) - factor * groebnerMatrix(15,147); groebnerMatrix(37,192) = groebnerMatrix(37,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(37,22); groebnerMatrix(37,22) = 0.0; groebnerMatrix(37,36) = groebnerMatrix(37,36) - factor * groebnerMatrix(24,160); groebnerMatrix(37,123) = groebnerMatrix(37,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(37,25); groebnerMatrix(37,25) = 0.0; groebnerMatrix(37,29) = groebnerMatrix(37,29) - factor * groebnerMatrix(14,153); groebnerMatrix(37,35) = groebnerMatrix(37,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(37,26); groebnerMatrix(37,26) = 0.0; groebnerMatrix(37,28) = groebnerMatrix(37,28) - factor * groebnerMatrix(19,152); groebnerMatrix(37,183) = groebnerMatrix(37,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(37,27); groebnerMatrix(37,27) = 0.0; groebnerMatrix(37,33) = groebnerMatrix(37,33) - factor * groebnerMatrix(28,157); groebnerMatrix(37,175) = groebnerMatrix(37,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(37,30); groebnerMatrix(37,30) = 0.0; groebnerMatrix(37,34) = groebnerMatrix(37,34) - factor * groebnerMatrix(16,158); groebnerMatrix(37,168) = groebnerMatrix(37,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(37,39); groebnerMatrix(37,39) = 0.0; groebnerMatrix(37,63) = groebnerMatrix(37,63) - factor * groebnerMatrix(12,171); groebnerMatrix(37,101) = groebnerMatrix(37,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,40); groebnerMatrix(37,40) = 0.0; groebnerMatrix(37,62) = groebnerMatrix(37,62) - factor * groebnerMatrix(20,170); groebnerMatrix(37,158) = groebnerMatrix(37,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(37,41); groebnerMatrix(37,41) = 0.0; groebnerMatrix(37,65) = groebnerMatrix(37,65) - factor * groebnerMatrix(12,171); groebnerMatrix(37,102) = groebnerMatrix(37,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,42); groebnerMatrix(37,42) = 0.0; groebnerMatrix(37,64) = groebnerMatrix(37,64) - factor * groebnerMatrix(20,170); groebnerMatrix(37,159) = groebnerMatrix(37,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(37,43); groebnerMatrix(37,43) = 0.0; groebnerMatrix(37,56) = groebnerMatrix(37,56) - factor * groebnerMatrix(22,162); groebnerMatrix(37,139) = groebnerMatrix(37,139) - factor * groebnerMatrix(22,186); groebnerMatrix(37,193) = groebnerMatrix(37,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(37,44); groebnerMatrix(37,44) = 0.0; groebnerMatrix(37,72) = groebnerMatrix(37,72) - factor * groebnerMatrix(11,174); groebnerMatrix(37,113) = groebnerMatrix(37,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(37,45); groebnerMatrix(37,45) = 0.0; groebnerMatrix(37,73) = groebnerMatrix(37,73) - factor * groebnerMatrix(11,174); groebnerMatrix(37,114) = groebnerMatrix(37,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(37,46); groebnerMatrix(37,46) = 0.0; groebnerMatrix(37,72) = groebnerMatrix(37,72) - factor * groebnerMatrix(12,171); groebnerMatrix(37,109) = groebnerMatrix(37,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,47); groebnerMatrix(37,47) = 0.0; groebnerMatrix(37,71) = groebnerMatrix(37,71) - factor * groebnerMatrix(20,170); groebnerMatrix(37,161) = groebnerMatrix(37,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(37,48); groebnerMatrix(37,48) = 0.0; groebnerMatrix(37,52) = groebnerMatrix(37,52) - factor * groebnerMatrix(16,158); groebnerMatrix(37,169) = groebnerMatrix(37,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(37,49); groebnerMatrix(37,49) = 0.0; groebnerMatrix(37,75) = groebnerMatrix(37,75) - factor * groebnerMatrix(11,174); groebnerMatrix(37,116) = groebnerMatrix(37,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(37,50); groebnerMatrix(37,50) = 0.0; groebnerMatrix(37,74) = groebnerMatrix(37,74) - factor * groebnerMatrix(21,173); groebnerMatrix(37,154) = groebnerMatrix(37,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(37,51); groebnerMatrix(37,51) = 0.0; groebnerMatrix(37,77) = groebnerMatrix(37,77) - factor * groebnerMatrix(12,171); groebnerMatrix(37,114) = groebnerMatrix(37,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,52); groebnerMatrix(37,52) = 0.0; groebnerMatrix(37,76) = groebnerMatrix(37,76) - factor * groebnerMatrix(20,170); groebnerMatrix(37,162) = groebnerMatrix(37,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(37,53); groebnerMatrix(37,53) = 0.0; groebnerMatrix(37,105) = groebnerMatrix(37,105) - factor * groebnerMatrix(27,181); groebnerMatrix(37,146) = groebnerMatrix(37,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(37,54); groebnerMatrix(37,54) = 0.0; groebnerMatrix(37,80) = groebnerMatrix(37,80) - factor * groebnerMatrix(11,174); groebnerMatrix(37,117) = groebnerMatrix(37,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(37,55); groebnerMatrix(37,55) = 0.0; groebnerMatrix(37,79) = groebnerMatrix(37,79) - factor * groebnerMatrix(21,173); groebnerMatrix(37,159) = groebnerMatrix(37,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(37,56); groebnerMatrix(37,56) = 0.0; groebnerMatrix(37,115) = groebnerMatrix(37,115) - factor * groebnerMatrix(27,181); groebnerMatrix(37,158) = groebnerMatrix(37,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(37,57); groebnerMatrix(37,57) = 0.0; groebnerMatrix(37,90) = groebnerMatrix(37,90) - factor * groebnerMatrix(10,177); groebnerMatrix(37,134) = groebnerMatrix(37,134) - factor * groebnerMatrix(10,186); groebnerMatrix(37,188) = groebnerMatrix(37,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(37,58); groebnerMatrix(37,58) = 0.0; groebnerMatrix(37,91) = groebnerMatrix(37,91) - factor * groebnerMatrix(10,177); groebnerMatrix(37,135) = groebnerMatrix(37,135) - factor * groebnerMatrix(10,186); groebnerMatrix(37,189) = groebnerMatrix(37,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(37,59); groebnerMatrix(37,59) = 0.0; groebnerMatrix(37,93) = groebnerMatrix(37,93) - factor * groebnerMatrix(10,177); groebnerMatrix(37,137) = groebnerMatrix(37,137) - factor * groebnerMatrix(10,186); groebnerMatrix(37,191) = groebnerMatrix(37,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(37,60); groebnerMatrix(37,60) = 0.0; groebnerMatrix(37,94) = groebnerMatrix(37,94) - factor * groebnerMatrix(10,177); groebnerMatrix(37,138) = groebnerMatrix(37,138) - factor * groebnerMatrix(10,186); groebnerMatrix(37,192) = groebnerMatrix(37,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(37,61); groebnerMatrix(37,61) = 0.0; groebnerMatrix(37,63) = groebnerMatrix(37,63) - factor * groebnerMatrix(15,144); groebnerMatrix(37,66) = groebnerMatrix(37,66) - factor * groebnerMatrix(15,147); groebnerMatrix(37,194) = groebnerMatrix(37,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(37,64); groebnerMatrix(37,64) = 0.0; groebnerMatrix(37,98) = groebnerMatrix(37,98) - factor * groebnerMatrix(17,179); groebnerMatrix(37,148) = groebnerMatrix(37,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(37,65); groebnerMatrix(37,65) = 0.0; groebnerMatrix(37,99) = groebnerMatrix(37,99) - factor * groebnerMatrix(17,179); groebnerMatrix(37,149) = groebnerMatrix(37,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(37,66); groebnerMatrix(37,66) = 0.0; groebnerMatrix(37,101) = groebnerMatrix(37,101) - factor * groebnerMatrix(17,179); groebnerMatrix(37,150) = groebnerMatrix(37,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(37,67); groebnerMatrix(37,67) = 0.0; groebnerMatrix(37,72) = groebnerMatrix(37,72) - factor * groebnerMatrix(14,153); groebnerMatrix(37,78) = groebnerMatrix(37,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(37,68); groebnerMatrix(37,68) = 0.0; groebnerMatrix(37,71) = groebnerMatrix(37,71) - factor * groebnerMatrix(19,152); groebnerMatrix(37,185) = groebnerMatrix(37,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(37,69); groebnerMatrix(37,69) = 0.0; groebnerMatrix(37,104) = groebnerMatrix(37,104) - factor * groebnerMatrix(17,179); groebnerMatrix(37,151) = groebnerMatrix(37,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(37,70); groebnerMatrix(37,70) = 0.0; groebnerMatrix(37,75) = groebnerMatrix(37,75) - factor * groebnerMatrix(13,156); groebnerMatrix(37,81) = groebnerMatrix(37,81) - factor * groebnerMatrix(13,162); groebnerMatrix(37,194) = groebnerMatrix(37,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(37,73); groebnerMatrix(37,73) = 0.0; groebnerMatrix(37,77) = groebnerMatrix(37,77) - factor * groebnerMatrix(16,158); groebnerMatrix(37,176) = groebnerMatrix(37,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(37,76); groebnerMatrix(37,76) = 0.0; groebnerMatrix(37,107) = groebnerMatrix(37,107) - factor * groebnerMatrix(18,182); groebnerMatrix(37,142) = groebnerMatrix(37,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(37,77); groebnerMatrix(37,77) = 0.0; groebnerMatrix(37,108) = groebnerMatrix(37,108) - factor * groebnerMatrix(18,182); groebnerMatrix(37,143) = groebnerMatrix(37,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(37,78); groebnerMatrix(37,78) = 0.0; groebnerMatrix(37,113) = groebnerMatrix(37,113) - factor * groebnerMatrix(17,179); groebnerMatrix(37,160) = groebnerMatrix(37,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(37,79); groebnerMatrix(37,79) = 0.0; groebnerMatrix(37,110) = groebnerMatrix(37,110) - factor * groebnerMatrix(18,182); groebnerMatrix(37,148) = groebnerMatrix(37,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(37,80); groebnerMatrix(37,80) = 0.0; groebnerMatrix(37,111) = groebnerMatrix(37,111) - factor * groebnerMatrix(18,182); groebnerMatrix(37,152) = groebnerMatrix(37,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(37,81); groebnerMatrix(37,81) = 0.0; groebnerMatrix(37,116) = groebnerMatrix(37,116) - factor * groebnerMatrix(18,182); groebnerMatrix(37,157) = groebnerMatrix(37,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(37,82); groebnerMatrix(37,82) = 0.0; groebnerMatrix(37,90) = groebnerMatrix(37,90) - factor * groebnerMatrix(12,171); groebnerMatrix(37,127) = groebnerMatrix(37,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,83); groebnerMatrix(37,83) = 0.0; groebnerMatrix(37,89) = groebnerMatrix(37,89) - factor * groebnerMatrix(20,170); groebnerMatrix(37,175) = groebnerMatrix(37,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(37,84); groebnerMatrix(37,84) = 0.0; groebnerMatrix(37,119) = groebnerMatrix(37,119) - factor * groebnerMatrix(17,179); groebnerMatrix(37,166) = groebnerMatrix(37,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(37,85); groebnerMatrix(37,85) = 0.0; groebnerMatrix(37,93) = groebnerMatrix(37,93) - factor * groebnerMatrix(11,174); groebnerMatrix(37,130) = groebnerMatrix(37,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(37,86); groebnerMatrix(37,86) = 0.0; groebnerMatrix(37,92) = groebnerMatrix(37,92) - factor * groebnerMatrix(21,173); groebnerMatrix(37,172) = groebnerMatrix(37,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(37,87); groebnerMatrix(37,87) = 0.0; groebnerMatrix(37,122) = groebnerMatrix(37,122) - factor * groebnerMatrix(18,182); groebnerMatrix(37,163) = groebnerMatrix(37,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(37,91); groebnerMatrix(37,91) = 0.0; groebnerMatrix(37,126) = groebnerMatrix(37,126) - factor * groebnerMatrix(17,179); groebnerMatrix(37,173) = groebnerMatrix(37,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(37,94); groebnerMatrix(37,94) = 0.0; groebnerMatrix(37,129) = groebnerMatrix(37,129) - factor * groebnerMatrix(18,182); groebnerMatrix(37,170) = groebnerMatrix(37,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(37,97); groebnerMatrix(37,97) = 0.0; groebnerMatrix(37,99) = groebnerMatrix(37,99) - factor * groebnerMatrix(15,144); groebnerMatrix(37,102) = groebnerMatrix(37,102) - factor * groebnerMatrix(15,147); groebnerMatrix(37,195) = groebnerMatrix(37,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(37,100); groebnerMatrix(37,100) = 0.0; groebnerMatrix(37,115) = groebnerMatrix(37,115) - factor * groebnerMatrix(24,160); groebnerMatrix(37,139) = groebnerMatrix(37,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(37,103); groebnerMatrix(37,103) = 0.0; groebnerMatrix(37,108) = groebnerMatrix(37,108) - factor * groebnerMatrix(14,153); groebnerMatrix(37,114) = groebnerMatrix(37,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(37,104); groebnerMatrix(37,104) = 0.0; groebnerMatrix(37,107) = groebnerMatrix(37,107) - factor * groebnerMatrix(19,152); groebnerMatrix(37,186) = groebnerMatrix(37,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(37,105); groebnerMatrix(37,105) = 0.0; groebnerMatrix(37,112) = groebnerMatrix(37,112) - factor * groebnerMatrix(28,157); groebnerMatrix(37,185) = groebnerMatrix(37,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(37,106); groebnerMatrix(37,106) = 0.0; groebnerMatrix(37,111) = groebnerMatrix(37,111) - factor * groebnerMatrix(13,156); groebnerMatrix(37,117) = groebnerMatrix(37,117) - factor * groebnerMatrix(13,162); groebnerMatrix(37,195) = groebnerMatrix(37,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(37,109); groebnerMatrix(37,109) = 0.0; groebnerMatrix(37,113) = groebnerMatrix(37,113) - factor * groebnerMatrix(16,158); groebnerMatrix(37,184) = groebnerMatrix(37,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(37,118); groebnerMatrix(37,118) = 0.0; groebnerMatrix(37,126) = groebnerMatrix(37,126) - factor * groebnerMatrix(12,171); groebnerMatrix(37,135) = groebnerMatrix(37,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,119); groebnerMatrix(37,119) = 0.0; groebnerMatrix(37,125) = groebnerMatrix(37,125) - factor * groebnerMatrix(20,170); groebnerMatrix(37,183) = groebnerMatrix(37,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(37,120); groebnerMatrix(37,120) = 0.0; groebnerMatrix(37,133) = groebnerMatrix(37,133) - factor * groebnerMatrix(29,178); groebnerMatrix(37,182) = groebnerMatrix(37,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(37,121); groebnerMatrix(37,121) = 0.0; groebnerMatrix(37,129) = groebnerMatrix(37,129) - factor * groebnerMatrix(11,174); groebnerMatrix(37,138) = groebnerMatrix(37,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(37,122); groebnerMatrix(37,122) = 0.0; groebnerMatrix(37,128) = groebnerMatrix(37,128) - factor * groebnerMatrix(21,173); groebnerMatrix(37,180) = groebnerMatrix(37,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(37,123); groebnerMatrix(37,123) = 0.0; groebnerMatrix(37,136) = groebnerMatrix(37,136) - factor * groebnerMatrix(27,181); groebnerMatrix(37,179) = groebnerMatrix(37,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(37,127); groebnerMatrix(37,127) = 0.0; groebnerMatrix(37,134) = groebnerMatrix(37,134) - factor * groebnerMatrix(17,179); groebnerMatrix(37,181) = groebnerMatrix(37,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(37,130); groebnerMatrix(37,130) = 0.0; groebnerMatrix(37,137) = groebnerMatrix(37,137) - factor * groebnerMatrix(18,182); groebnerMatrix(37,178) = groebnerMatrix(37,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(37,142); groebnerMatrix(37,142) = 0.0; groebnerMatrix(37,144) = groebnerMatrix(37,144) - factor * groebnerMatrix(15,144); groebnerMatrix(37,147) = groebnerMatrix(37,147) - factor * groebnerMatrix(15,147); groebnerMatrix(37,196) = groebnerMatrix(37,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(37,143); groebnerMatrix(37,143) = 0.0; groebnerMatrix(37,155) = groebnerMatrix(37,155) - factor * groebnerMatrix(26,155); groebnerMatrix(37,176) = groebnerMatrix(37,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(37,144); groebnerMatrix(37,144) = 0.0; groebnerMatrix(37,156) = groebnerMatrix(37,156) - factor * groebnerMatrix(25,156); groebnerMatrix(37,177) = groebnerMatrix(37,177) - factor * groebnerMatrix(25,177); groebnerMatrix(37,196) = groebnerMatrix(37,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(37,146); groebnerMatrix(37,146) = 0.0; groebnerMatrix(37,161) = groebnerMatrix(37,161) - factor * groebnerMatrix(23,161); groebnerMatrix(37,185) = groebnerMatrix(37,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(37,147); groebnerMatrix(37,147) = 0.0; groebnerMatrix(37,162) = groebnerMatrix(37,162) - factor * groebnerMatrix(22,162); groebnerMatrix(37,186) = groebnerMatrix(37,186) - factor * groebnerMatrix(22,186); groebnerMatrix(37,196) = groebnerMatrix(37,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(37,148); groebnerMatrix(37,148) = 0.0; groebnerMatrix(37,153) = groebnerMatrix(37,153) - factor * groebnerMatrix(14,153); groebnerMatrix(37,159) = groebnerMatrix(37,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(37,149); groebnerMatrix(37,149) = 0.0; groebnerMatrix(37,152) = groebnerMatrix(37,152) - factor * groebnerMatrix(19,152); groebnerMatrix(37,195) = groebnerMatrix(37,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(37,150); groebnerMatrix(37,150) = 0.0; groebnerMatrix(37,157) = groebnerMatrix(37,157) - factor * groebnerMatrix(28,157); groebnerMatrix(37,194) = groebnerMatrix(37,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(37,151); groebnerMatrix(37,151) = 0.0; groebnerMatrix(37,156) = groebnerMatrix(37,156) - factor * groebnerMatrix(13,156); groebnerMatrix(37,162) = groebnerMatrix(37,162) - factor * groebnerMatrix(13,162); groebnerMatrix(37,196) = groebnerMatrix(37,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,37); groebnerRow31_000000000_f(groebnerMatrix,37); factor = -groebnerMatrix(37,154); groebnerMatrix(37,154) = 0.0; groebnerMatrix(37,158) = groebnerMatrix(37,158) - factor * groebnerMatrix(16,158); groebnerMatrix(37,193) = groebnerMatrix(37,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,37); groebnerRow33_000000000_f(groebnerMatrix,37); groebnerRow34_000000000_f(groebnerMatrix,37); groebnerRow35_000000000_f(groebnerMatrix,37); groebnerRow36_000000000_f(groebnerMatrix,37); factor = groebnerMatrix(37,163); groebnerMatrix(37,163) = 0.0; groebnerMatrix(37,171) = groebnerMatrix(37,171) - factor * groebnerMatrix(12,171); groebnerMatrix(37,180) = groebnerMatrix(37,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(37,164); groebnerMatrix(37,164) = 0.0; groebnerMatrix(37,170) = groebnerMatrix(37,170) - factor * groebnerMatrix(20,170); groebnerMatrix(37,192) = groebnerMatrix(37,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(37,165); groebnerMatrix(37,165) = 0.0; groebnerMatrix(37,178) = groebnerMatrix(37,178) - factor * groebnerMatrix(29,178); groebnerMatrix(37,191) = groebnerMatrix(37,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(37,166); groebnerMatrix(37,166) = 0.0; groebnerMatrix(37,174) = groebnerMatrix(37,174) - factor * groebnerMatrix(11,174); groebnerMatrix(37,183) = groebnerMatrix(37,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(37,167); groebnerMatrix(37,167) = 0.0; groebnerMatrix(37,173) = groebnerMatrix(37,173) - factor * groebnerMatrix(21,173); groebnerMatrix(37,189) = groebnerMatrix(37,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(37,168); groebnerMatrix(37,168) = 0.0; groebnerMatrix(37,181) = groebnerMatrix(37,181) - factor * groebnerMatrix(27,181); groebnerMatrix(37,188) = groebnerMatrix(37,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(37,169); groebnerMatrix(37,169) = 0.0; groebnerMatrix(37,177) = groebnerMatrix(37,177) - factor * groebnerMatrix(10,177); groebnerMatrix(37,186) = groebnerMatrix(37,186) - factor * groebnerMatrix(10,186); groebnerMatrix(37,196) = groebnerMatrix(37,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(37,172); groebnerMatrix(37,172) = 0.0; groebnerMatrix(37,179) = groebnerMatrix(37,179) - factor * groebnerMatrix(17,179); groebnerMatrix(37,190) = groebnerMatrix(37,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(37,175); groebnerMatrix(37,175) = 0.0; groebnerMatrix(37,182) = groebnerMatrix(37,182) - factor * groebnerMatrix(18,182); groebnerMatrix(37,187) = groebnerMatrix(37,187) - factor * groebnerMatrix(18,187); sPolynomial38(groebnerMatrix); factor = -groebnerMatrix(38,1); groebnerMatrix(38,1) = 0.0; groebnerMatrix(38,8) = groebnerMatrix(38,8) - factor * groebnerMatrix(19,152); groebnerMatrix(38,179) = groebnerMatrix(38,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(38,2); groebnerMatrix(38,2) = 0.0; groebnerMatrix(38,11) = groebnerMatrix(38,11) - factor * groebnerMatrix(14,153); groebnerMatrix(38,24) = groebnerMatrix(38,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(38,3); groebnerMatrix(38,3) = 0.0; groebnerMatrix(38,10) = groebnerMatrix(38,10) - factor * groebnerMatrix(19,152); groebnerMatrix(38,180) = groebnerMatrix(38,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(38,4); groebnerMatrix(38,4) = 0.0; groebnerMatrix(38,36) = groebnerMatrix(38,36) - factor * groebnerMatrix(22,162); groebnerMatrix(38,136) = groebnerMatrix(38,136) - factor * groebnerMatrix(22,186); groebnerMatrix(38,190) = groebnerMatrix(38,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(38,5); groebnerMatrix(38,5) = 0.0; groebnerMatrix(38,17) = groebnerMatrix(38,17) - factor * groebnerMatrix(13,156); groebnerMatrix(38,34) = groebnerMatrix(38,34) - factor * groebnerMatrix(13,162); groebnerMatrix(38,188) = groebnerMatrix(38,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(38,6); groebnerMatrix(38,6) = 0.0; groebnerMatrix(38,18) = groebnerMatrix(38,18) - factor * groebnerMatrix(13,156); groebnerMatrix(38,35) = groebnerMatrix(38,35) - factor * groebnerMatrix(13,162); groebnerMatrix(38,189) = groebnerMatrix(38,189) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(38,10); groebnerMatrix(38,10) = 0.0; groebnerMatrix(38,20) = groebnerMatrix(38,20) - factor * groebnerMatrix(16,158); groebnerMatrix(38,163) = groebnerMatrix(38,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(38,11); groebnerMatrix(38,11) = 0.0; groebnerMatrix(38,21) = groebnerMatrix(38,21) - factor * groebnerMatrix(16,158); groebnerMatrix(38,164) = groebnerMatrix(38,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(38,12); groebnerMatrix(38,12) = 0.0; groebnerMatrix(38,23) = groebnerMatrix(38,23) - factor * groebnerMatrix(16,158); groebnerMatrix(38,165) = groebnerMatrix(38,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(38,13); groebnerMatrix(38,13) = 0.0; groebnerMatrix(38,17) = groebnerMatrix(38,17) - factor * groebnerMatrix(14,153); groebnerMatrix(38,30) = groebnerMatrix(38,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(38,14); groebnerMatrix(38,14) = 0.0; groebnerMatrix(38,16) = groebnerMatrix(38,16) - factor * groebnerMatrix(19,152); groebnerMatrix(38,182) = groebnerMatrix(38,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(38,15); groebnerMatrix(38,15) = 0.0; groebnerMatrix(38,26) = groebnerMatrix(38,26) - factor * groebnerMatrix(16,158); groebnerMatrix(38,166) = groebnerMatrix(38,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(38,18); groebnerMatrix(38,18) = 0.0; groebnerMatrix(38,29) = groebnerMatrix(38,29) - factor * groebnerMatrix(16,158); groebnerMatrix(38,167) = groebnerMatrix(38,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(38,19); groebnerMatrix(38,19) = 0.0; groebnerMatrix(38,21) = groebnerMatrix(38,21) - factor * groebnerMatrix(15,144); groebnerMatrix(38,24) = groebnerMatrix(38,24) - factor * groebnerMatrix(15,147); groebnerMatrix(38,192) = groebnerMatrix(38,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(38,22); groebnerMatrix(38,22) = 0.0; groebnerMatrix(38,36) = groebnerMatrix(38,36) - factor * groebnerMatrix(24,160); groebnerMatrix(38,123) = groebnerMatrix(38,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(38,25); groebnerMatrix(38,25) = 0.0; groebnerMatrix(38,29) = groebnerMatrix(38,29) - factor * groebnerMatrix(14,153); groebnerMatrix(38,35) = groebnerMatrix(38,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(38,26); groebnerMatrix(38,26) = 0.0; groebnerMatrix(38,28) = groebnerMatrix(38,28) - factor * groebnerMatrix(19,152); groebnerMatrix(38,183) = groebnerMatrix(38,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(38,27); groebnerMatrix(38,27) = 0.0; groebnerMatrix(38,33) = groebnerMatrix(38,33) - factor * groebnerMatrix(28,157); groebnerMatrix(38,175) = groebnerMatrix(38,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(38,30); groebnerMatrix(38,30) = 0.0; groebnerMatrix(38,34) = groebnerMatrix(38,34) - factor * groebnerMatrix(16,158); groebnerMatrix(38,168) = groebnerMatrix(38,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(38,39); groebnerMatrix(38,39) = 0.0; groebnerMatrix(38,63) = groebnerMatrix(38,63) - factor * groebnerMatrix(12,171); groebnerMatrix(38,101) = groebnerMatrix(38,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,40); groebnerMatrix(38,40) = 0.0; groebnerMatrix(38,62) = groebnerMatrix(38,62) - factor * groebnerMatrix(20,170); groebnerMatrix(38,158) = groebnerMatrix(38,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(38,41); groebnerMatrix(38,41) = 0.0; groebnerMatrix(38,65) = groebnerMatrix(38,65) - factor * groebnerMatrix(12,171); groebnerMatrix(38,102) = groebnerMatrix(38,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,42); groebnerMatrix(38,42) = 0.0; groebnerMatrix(38,64) = groebnerMatrix(38,64) - factor * groebnerMatrix(20,170); groebnerMatrix(38,159) = groebnerMatrix(38,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(38,43); groebnerMatrix(38,43) = 0.0; groebnerMatrix(38,56) = groebnerMatrix(38,56) - factor * groebnerMatrix(22,162); groebnerMatrix(38,139) = groebnerMatrix(38,139) - factor * groebnerMatrix(22,186); groebnerMatrix(38,193) = groebnerMatrix(38,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(38,44); groebnerMatrix(38,44) = 0.0; groebnerMatrix(38,72) = groebnerMatrix(38,72) - factor * groebnerMatrix(11,174); groebnerMatrix(38,113) = groebnerMatrix(38,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(38,45); groebnerMatrix(38,45) = 0.0; groebnerMatrix(38,73) = groebnerMatrix(38,73) - factor * groebnerMatrix(11,174); groebnerMatrix(38,114) = groebnerMatrix(38,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(38,46); groebnerMatrix(38,46) = 0.0; groebnerMatrix(38,72) = groebnerMatrix(38,72) - factor * groebnerMatrix(12,171); groebnerMatrix(38,109) = groebnerMatrix(38,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,47); groebnerMatrix(38,47) = 0.0; groebnerMatrix(38,71) = groebnerMatrix(38,71) - factor * groebnerMatrix(20,170); groebnerMatrix(38,161) = groebnerMatrix(38,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(38,48); groebnerMatrix(38,48) = 0.0; groebnerMatrix(38,52) = groebnerMatrix(38,52) - factor * groebnerMatrix(16,158); groebnerMatrix(38,169) = groebnerMatrix(38,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(38,49); groebnerMatrix(38,49) = 0.0; groebnerMatrix(38,75) = groebnerMatrix(38,75) - factor * groebnerMatrix(11,174); groebnerMatrix(38,116) = groebnerMatrix(38,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(38,50); groebnerMatrix(38,50) = 0.0; groebnerMatrix(38,74) = groebnerMatrix(38,74) - factor * groebnerMatrix(21,173); groebnerMatrix(38,154) = groebnerMatrix(38,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(38,51); groebnerMatrix(38,51) = 0.0; groebnerMatrix(38,77) = groebnerMatrix(38,77) - factor * groebnerMatrix(12,171); groebnerMatrix(38,114) = groebnerMatrix(38,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,52); groebnerMatrix(38,52) = 0.0; groebnerMatrix(38,76) = groebnerMatrix(38,76) - factor * groebnerMatrix(20,170); groebnerMatrix(38,162) = groebnerMatrix(38,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(38,53); groebnerMatrix(38,53) = 0.0; groebnerMatrix(38,105) = groebnerMatrix(38,105) - factor * groebnerMatrix(27,181); groebnerMatrix(38,146) = groebnerMatrix(38,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(38,54); groebnerMatrix(38,54) = 0.0; groebnerMatrix(38,80) = groebnerMatrix(38,80) - factor * groebnerMatrix(11,174); groebnerMatrix(38,117) = groebnerMatrix(38,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(38,55); groebnerMatrix(38,55) = 0.0; groebnerMatrix(38,79) = groebnerMatrix(38,79) - factor * groebnerMatrix(21,173); groebnerMatrix(38,159) = groebnerMatrix(38,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(38,56); groebnerMatrix(38,56) = 0.0; groebnerMatrix(38,115) = groebnerMatrix(38,115) - factor * groebnerMatrix(27,181); groebnerMatrix(38,158) = groebnerMatrix(38,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(38,57); groebnerMatrix(38,57) = 0.0; groebnerMatrix(38,90) = groebnerMatrix(38,90) - factor * groebnerMatrix(10,177); groebnerMatrix(38,134) = groebnerMatrix(38,134) - factor * groebnerMatrix(10,186); groebnerMatrix(38,188) = groebnerMatrix(38,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(38,58); groebnerMatrix(38,58) = 0.0; groebnerMatrix(38,91) = groebnerMatrix(38,91) - factor * groebnerMatrix(10,177); groebnerMatrix(38,135) = groebnerMatrix(38,135) - factor * groebnerMatrix(10,186); groebnerMatrix(38,189) = groebnerMatrix(38,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(38,59); groebnerMatrix(38,59) = 0.0; groebnerMatrix(38,93) = groebnerMatrix(38,93) - factor * groebnerMatrix(10,177); groebnerMatrix(38,137) = groebnerMatrix(38,137) - factor * groebnerMatrix(10,186); groebnerMatrix(38,191) = groebnerMatrix(38,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(38,60); groebnerMatrix(38,60) = 0.0; groebnerMatrix(38,94) = groebnerMatrix(38,94) - factor * groebnerMatrix(10,177); groebnerMatrix(38,138) = groebnerMatrix(38,138) - factor * groebnerMatrix(10,186); groebnerMatrix(38,192) = groebnerMatrix(38,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(38,61); groebnerMatrix(38,61) = 0.0; groebnerMatrix(38,63) = groebnerMatrix(38,63) - factor * groebnerMatrix(15,144); groebnerMatrix(38,66) = groebnerMatrix(38,66) - factor * groebnerMatrix(15,147); groebnerMatrix(38,194) = groebnerMatrix(38,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(38,64); groebnerMatrix(38,64) = 0.0; groebnerMatrix(38,98) = groebnerMatrix(38,98) - factor * groebnerMatrix(17,179); groebnerMatrix(38,148) = groebnerMatrix(38,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(38,65); groebnerMatrix(38,65) = 0.0; groebnerMatrix(38,99) = groebnerMatrix(38,99) - factor * groebnerMatrix(17,179); groebnerMatrix(38,149) = groebnerMatrix(38,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(38,66); groebnerMatrix(38,66) = 0.0; groebnerMatrix(38,101) = groebnerMatrix(38,101) - factor * groebnerMatrix(17,179); groebnerMatrix(38,150) = groebnerMatrix(38,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(38,67); groebnerMatrix(38,67) = 0.0; groebnerMatrix(38,72) = groebnerMatrix(38,72) - factor * groebnerMatrix(14,153); groebnerMatrix(38,78) = groebnerMatrix(38,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(38,68); groebnerMatrix(38,68) = 0.0; groebnerMatrix(38,71) = groebnerMatrix(38,71) - factor * groebnerMatrix(19,152); groebnerMatrix(38,185) = groebnerMatrix(38,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(38,69); groebnerMatrix(38,69) = 0.0; groebnerMatrix(38,104) = groebnerMatrix(38,104) - factor * groebnerMatrix(17,179); groebnerMatrix(38,151) = groebnerMatrix(38,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(38,70); groebnerMatrix(38,70) = 0.0; groebnerMatrix(38,75) = groebnerMatrix(38,75) - factor * groebnerMatrix(13,156); groebnerMatrix(38,81) = groebnerMatrix(38,81) - factor * groebnerMatrix(13,162); groebnerMatrix(38,194) = groebnerMatrix(38,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(38,73); groebnerMatrix(38,73) = 0.0; groebnerMatrix(38,77) = groebnerMatrix(38,77) - factor * groebnerMatrix(16,158); groebnerMatrix(38,176) = groebnerMatrix(38,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(38,76); groebnerMatrix(38,76) = 0.0; groebnerMatrix(38,107) = groebnerMatrix(38,107) - factor * groebnerMatrix(18,182); groebnerMatrix(38,142) = groebnerMatrix(38,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(38,77); groebnerMatrix(38,77) = 0.0; groebnerMatrix(38,108) = groebnerMatrix(38,108) - factor * groebnerMatrix(18,182); groebnerMatrix(38,143) = groebnerMatrix(38,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(38,78); groebnerMatrix(38,78) = 0.0; groebnerMatrix(38,113) = groebnerMatrix(38,113) - factor * groebnerMatrix(17,179); groebnerMatrix(38,160) = groebnerMatrix(38,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(38,79); groebnerMatrix(38,79) = 0.0; groebnerMatrix(38,110) = groebnerMatrix(38,110) - factor * groebnerMatrix(18,182); groebnerMatrix(38,148) = groebnerMatrix(38,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(38,80); groebnerMatrix(38,80) = 0.0; groebnerMatrix(38,111) = groebnerMatrix(38,111) - factor * groebnerMatrix(18,182); groebnerMatrix(38,152) = groebnerMatrix(38,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(38,81); groebnerMatrix(38,81) = 0.0; groebnerMatrix(38,116) = groebnerMatrix(38,116) - factor * groebnerMatrix(18,182); groebnerMatrix(38,157) = groebnerMatrix(38,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(38,82); groebnerMatrix(38,82) = 0.0; groebnerMatrix(38,90) = groebnerMatrix(38,90) - factor * groebnerMatrix(12,171); groebnerMatrix(38,127) = groebnerMatrix(38,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,83); groebnerMatrix(38,83) = 0.0; groebnerMatrix(38,89) = groebnerMatrix(38,89) - factor * groebnerMatrix(20,170); groebnerMatrix(38,175) = groebnerMatrix(38,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(38,84); groebnerMatrix(38,84) = 0.0; groebnerMatrix(38,119) = groebnerMatrix(38,119) - factor * groebnerMatrix(17,179); groebnerMatrix(38,166) = groebnerMatrix(38,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(38,85); groebnerMatrix(38,85) = 0.0; groebnerMatrix(38,93) = groebnerMatrix(38,93) - factor * groebnerMatrix(11,174); groebnerMatrix(38,130) = groebnerMatrix(38,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(38,86); groebnerMatrix(38,86) = 0.0; groebnerMatrix(38,92) = groebnerMatrix(38,92) - factor * groebnerMatrix(21,173); groebnerMatrix(38,172) = groebnerMatrix(38,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(38,87); groebnerMatrix(38,87) = 0.0; groebnerMatrix(38,122) = groebnerMatrix(38,122) - factor * groebnerMatrix(18,182); groebnerMatrix(38,163) = groebnerMatrix(38,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(38,91); groebnerMatrix(38,91) = 0.0; groebnerMatrix(38,126) = groebnerMatrix(38,126) - factor * groebnerMatrix(17,179); groebnerMatrix(38,173) = groebnerMatrix(38,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(38,94); groebnerMatrix(38,94) = 0.0; groebnerMatrix(38,129) = groebnerMatrix(38,129) - factor * groebnerMatrix(18,182); groebnerMatrix(38,170) = groebnerMatrix(38,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(38,97); groebnerMatrix(38,97) = 0.0; groebnerMatrix(38,99) = groebnerMatrix(38,99) - factor * groebnerMatrix(15,144); groebnerMatrix(38,102) = groebnerMatrix(38,102) - factor * groebnerMatrix(15,147); groebnerMatrix(38,195) = groebnerMatrix(38,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(38,100); groebnerMatrix(38,100) = 0.0; groebnerMatrix(38,115) = groebnerMatrix(38,115) - factor * groebnerMatrix(24,160); groebnerMatrix(38,139) = groebnerMatrix(38,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(38,103); groebnerMatrix(38,103) = 0.0; groebnerMatrix(38,108) = groebnerMatrix(38,108) - factor * groebnerMatrix(14,153); groebnerMatrix(38,114) = groebnerMatrix(38,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(38,104); groebnerMatrix(38,104) = 0.0; groebnerMatrix(38,107) = groebnerMatrix(38,107) - factor * groebnerMatrix(19,152); groebnerMatrix(38,186) = groebnerMatrix(38,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(38,105); groebnerMatrix(38,105) = 0.0; groebnerMatrix(38,112) = groebnerMatrix(38,112) - factor * groebnerMatrix(28,157); groebnerMatrix(38,185) = groebnerMatrix(38,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(38,106); groebnerMatrix(38,106) = 0.0; groebnerMatrix(38,111) = groebnerMatrix(38,111) - factor * groebnerMatrix(13,156); groebnerMatrix(38,117) = groebnerMatrix(38,117) - factor * groebnerMatrix(13,162); groebnerMatrix(38,195) = groebnerMatrix(38,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(38,109); groebnerMatrix(38,109) = 0.0; groebnerMatrix(38,113) = groebnerMatrix(38,113) - factor * groebnerMatrix(16,158); groebnerMatrix(38,184) = groebnerMatrix(38,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(38,118); groebnerMatrix(38,118) = 0.0; groebnerMatrix(38,126) = groebnerMatrix(38,126) - factor * groebnerMatrix(12,171); groebnerMatrix(38,135) = groebnerMatrix(38,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,119); groebnerMatrix(38,119) = 0.0; groebnerMatrix(38,125) = groebnerMatrix(38,125) - factor * groebnerMatrix(20,170); groebnerMatrix(38,183) = groebnerMatrix(38,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(38,120); groebnerMatrix(38,120) = 0.0; groebnerMatrix(38,133) = groebnerMatrix(38,133) - factor * groebnerMatrix(29,178); groebnerMatrix(38,182) = groebnerMatrix(38,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(38,121); groebnerMatrix(38,121) = 0.0; groebnerMatrix(38,129) = groebnerMatrix(38,129) - factor * groebnerMatrix(11,174); groebnerMatrix(38,138) = groebnerMatrix(38,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(38,122); groebnerMatrix(38,122) = 0.0; groebnerMatrix(38,128) = groebnerMatrix(38,128) - factor * groebnerMatrix(21,173); groebnerMatrix(38,180) = groebnerMatrix(38,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(38,123); groebnerMatrix(38,123) = 0.0; groebnerMatrix(38,136) = groebnerMatrix(38,136) - factor * groebnerMatrix(27,181); groebnerMatrix(38,179) = groebnerMatrix(38,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(38,127); groebnerMatrix(38,127) = 0.0; groebnerMatrix(38,134) = groebnerMatrix(38,134) - factor * groebnerMatrix(17,179); groebnerMatrix(38,181) = groebnerMatrix(38,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(38,130); groebnerMatrix(38,130) = 0.0; groebnerMatrix(38,137) = groebnerMatrix(38,137) - factor * groebnerMatrix(18,182); groebnerMatrix(38,178) = groebnerMatrix(38,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(38,142); groebnerMatrix(38,142) = 0.0; groebnerMatrix(38,144) = groebnerMatrix(38,144) - factor * groebnerMatrix(15,144); groebnerMatrix(38,147) = groebnerMatrix(38,147) - factor * groebnerMatrix(15,147); groebnerMatrix(38,196) = groebnerMatrix(38,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(38,143); groebnerMatrix(38,143) = 0.0; groebnerMatrix(38,155) = groebnerMatrix(38,155) - factor * groebnerMatrix(26,155); groebnerMatrix(38,176) = groebnerMatrix(38,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(38,144); groebnerMatrix(38,144) = 0.0; groebnerMatrix(38,156) = groebnerMatrix(38,156) - factor * groebnerMatrix(25,156); groebnerMatrix(38,177) = groebnerMatrix(38,177) - factor * groebnerMatrix(25,177); groebnerMatrix(38,196) = groebnerMatrix(38,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(38,146); groebnerMatrix(38,146) = 0.0; groebnerMatrix(38,161) = groebnerMatrix(38,161) - factor * groebnerMatrix(23,161); groebnerMatrix(38,185) = groebnerMatrix(38,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(38,147); groebnerMatrix(38,147) = 0.0; groebnerMatrix(38,162) = groebnerMatrix(38,162) - factor * groebnerMatrix(22,162); groebnerMatrix(38,186) = groebnerMatrix(38,186) - factor * groebnerMatrix(22,186); groebnerMatrix(38,196) = groebnerMatrix(38,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(38,148); groebnerMatrix(38,148) = 0.0; groebnerMatrix(38,153) = groebnerMatrix(38,153) - factor * groebnerMatrix(14,153); groebnerMatrix(38,159) = groebnerMatrix(38,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(38,149); groebnerMatrix(38,149) = 0.0; groebnerMatrix(38,152) = groebnerMatrix(38,152) - factor * groebnerMatrix(19,152); groebnerMatrix(38,195) = groebnerMatrix(38,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(38,150); groebnerMatrix(38,150) = 0.0; groebnerMatrix(38,157) = groebnerMatrix(38,157) - factor * groebnerMatrix(28,157); groebnerMatrix(38,194) = groebnerMatrix(38,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(38,151); groebnerMatrix(38,151) = 0.0; groebnerMatrix(38,156) = groebnerMatrix(38,156) - factor * groebnerMatrix(13,156); groebnerMatrix(38,162) = groebnerMatrix(38,162) - factor * groebnerMatrix(13,162); groebnerMatrix(38,196) = groebnerMatrix(38,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,38); groebnerRow31_000000000_f(groebnerMatrix,38); factor = -groebnerMatrix(38,154); groebnerMatrix(38,154) = 0.0; groebnerMatrix(38,158) = groebnerMatrix(38,158) - factor * groebnerMatrix(16,158); groebnerMatrix(38,193) = groebnerMatrix(38,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,38); groebnerRow33_000000000_f(groebnerMatrix,38); groebnerRow34_000000000_f(groebnerMatrix,38); groebnerRow35_000000000_f(groebnerMatrix,38); groebnerRow36_000000000_f(groebnerMatrix,38); groebnerRow37_000000000_f(groebnerMatrix,38); factor = groebnerMatrix(38,163); groebnerMatrix(38,163) = 0.0; groebnerMatrix(38,171) = groebnerMatrix(38,171) - factor * groebnerMatrix(12,171); groebnerMatrix(38,180) = groebnerMatrix(38,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(38,164); groebnerMatrix(38,164) = 0.0; groebnerMatrix(38,170) = groebnerMatrix(38,170) - factor * groebnerMatrix(20,170); groebnerMatrix(38,192) = groebnerMatrix(38,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(38,165); groebnerMatrix(38,165) = 0.0; groebnerMatrix(38,178) = groebnerMatrix(38,178) - factor * groebnerMatrix(29,178); groebnerMatrix(38,191) = groebnerMatrix(38,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(38,166); groebnerMatrix(38,166) = 0.0; groebnerMatrix(38,174) = groebnerMatrix(38,174) - factor * groebnerMatrix(11,174); groebnerMatrix(38,183) = groebnerMatrix(38,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(38,167); groebnerMatrix(38,167) = 0.0; groebnerMatrix(38,173) = groebnerMatrix(38,173) - factor * groebnerMatrix(21,173); groebnerMatrix(38,189) = groebnerMatrix(38,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(38,168); groebnerMatrix(38,168) = 0.0; groebnerMatrix(38,181) = groebnerMatrix(38,181) - factor * groebnerMatrix(27,181); groebnerMatrix(38,188) = groebnerMatrix(38,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(38,169); groebnerMatrix(38,169) = 0.0; groebnerMatrix(38,177) = groebnerMatrix(38,177) - factor * groebnerMatrix(10,177); groebnerMatrix(38,186) = groebnerMatrix(38,186) - factor * groebnerMatrix(10,186); groebnerMatrix(38,196) = groebnerMatrix(38,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(38,172); groebnerMatrix(38,172) = 0.0; groebnerMatrix(38,179) = groebnerMatrix(38,179) - factor * groebnerMatrix(17,179); groebnerMatrix(38,190) = groebnerMatrix(38,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(38,175); groebnerMatrix(38,175) = 0.0; groebnerMatrix(38,182) = groebnerMatrix(38,182) - factor * groebnerMatrix(18,182); groebnerMatrix(38,187) = groebnerMatrix(38,187) - factor * groebnerMatrix(18,187); sPolynomial39(groebnerMatrix); factor = -groebnerMatrix(39,1); groebnerMatrix(39,1) = 0.0; groebnerMatrix(39,8) = groebnerMatrix(39,8) - factor * groebnerMatrix(19,152); groebnerMatrix(39,179) = groebnerMatrix(39,179) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(39,2); groebnerMatrix(39,2) = 0.0; groebnerMatrix(39,11) = groebnerMatrix(39,11) - factor * groebnerMatrix(14,153); groebnerMatrix(39,24) = groebnerMatrix(39,24) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(39,3); groebnerMatrix(39,3) = 0.0; groebnerMatrix(39,10) = groebnerMatrix(39,10) - factor * groebnerMatrix(19,152); groebnerMatrix(39,180) = groebnerMatrix(39,180) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(39,4); groebnerMatrix(39,4) = 0.0; groebnerMatrix(39,36) = groebnerMatrix(39,36) - factor * groebnerMatrix(22,162); groebnerMatrix(39,136) = groebnerMatrix(39,136) - factor * groebnerMatrix(22,186); groebnerMatrix(39,190) = groebnerMatrix(39,190) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(39,5); groebnerMatrix(39,5) = 0.0; groebnerMatrix(39,17) = groebnerMatrix(39,17) - factor * groebnerMatrix(13,156); groebnerMatrix(39,34) = groebnerMatrix(39,34) - factor * groebnerMatrix(13,162); groebnerMatrix(39,188) = groebnerMatrix(39,188) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(39,6); groebnerMatrix(39,6) = 0.0; groebnerMatrix(39,18) = groebnerMatrix(39,18) - factor * groebnerMatrix(13,156); groebnerMatrix(39,35) = groebnerMatrix(39,35) - factor * groebnerMatrix(13,162); groebnerMatrix(39,189) = groebnerMatrix(39,189) - factor * groebnerMatrix(13,196); factor = groebnerMatrix(39,7); groebnerMatrix(39,7) = 0.0; groebnerMatrix(39,9) = groebnerMatrix(39,9) - factor * groebnerMatrix(15,144); groebnerMatrix(39,12) = groebnerMatrix(39,12) - factor * groebnerMatrix(15,147); groebnerMatrix(39,191) = groebnerMatrix(39,191) - factor * groebnerMatrix(15,196); factor = -groebnerMatrix(39,10); groebnerMatrix(39,10) = 0.0; groebnerMatrix(39,20) = groebnerMatrix(39,20) - factor * groebnerMatrix(16,158); groebnerMatrix(39,163) = groebnerMatrix(39,163) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(39,11); groebnerMatrix(39,11) = 0.0; groebnerMatrix(39,21) = groebnerMatrix(39,21) - factor * groebnerMatrix(16,158); groebnerMatrix(39,164) = groebnerMatrix(39,164) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(39,12); groebnerMatrix(39,12) = 0.0; groebnerMatrix(39,23) = groebnerMatrix(39,23) - factor * groebnerMatrix(16,158); groebnerMatrix(39,165) = groebnerMatrix(39,165) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(39,13); groebnerMatrix(39,13) = 0.0; groebnerMatrix(39,17) = groebnerMatrix(39,17) - factor * groebnerMatrix(14,153); groebnerMatrix(39,30) = groebnerMatrix(39,30) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(39,14); groebnerMatrix(39,14) = 0.0; groebnerMatrix(39,16) = groebnerMatrix(39,16) - factor * groebnerMatrix(19,152); groebnerMatrix(39,182) = groebnerMatrix(39,182) - factor * groebnerMatrix(19,195); factor = -groebnerMatrix(39,15); groebnerMatrix(39,15) = 0.0; groebnerMatrix(39,26) = groebnerMatrix(39,26) - factor * groebnerMatrix(16,158); groebnerMatrix(39,166) = groebnerMatrix(39,166) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(39,18); groebnerMatrix(39,18) = 0.0; groebnerMatrix(39,29) = groebnerMatrix(39,29) - factor * groebnerMatrix(16,158); groebnerMatrix(39,167) = groebnerMatrix(39,167) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(39,19); groebnerMatrix(39,19) = 0.0; groebnerMatrix(39,21) = groebnerMatrix(39,21) - factor * groebnerMatrix(15,144); groebnerMatrix(39,24) = groebnerMatrix(39,24) - factor * groebnerMatrix(15,147); groebnerMatrix(39,192) = groebnerMatrix(39,192) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(39,22); groebnerMatrix(39,22) = 0.0; groebnerMatrix(39,36) = groebnerMatrix(39,36) - factor * groebnerMatrix(24,160); groebnerMatrix(39,123) = groebnerMatrix(39,123) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(39,25); groebnerMatrix(39,25) = 0.0; groebnerMatrix(39,29) = groebnerMatrix(39,29) - factor * groebnerMatrix(14,153); groebnerMatrix(39,35) = groebnerMatrix(39,35) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(39,26); groebnerMatrix(39,26) = 0.0; groebnerMatrix(39,28) = groebnerMatrix(39,28) - factor * groebnerMatrix(19,152); groebnerMatrix(39,183) = groebnerMatrix(39,183) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(39,27); groebnerMatrix(39,27) = 0.0; groebnerMatrix(39,33) = groebnerMatrix(39,33) - factor * groebnerMatrix(28,157); groebnerMatrix(39,175) = groebnerMatrix(39,175) - factor * groebnerMatrix(28,194); factor = -groebnerMatrix(39,30); groebnerMatrix(39,30) = 0.0; groebnerMatrix(39,34) = groebnerMatrix(39,34) - factor * groebnerMatrix(16,158); groebnerMatrix(39,168) = groebnerMatrix(39,168) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(39,39); groebnerMatrix(39,39) = 0.0; groebnerMatrix(39,63) = groebnerMatrix(39,63) - factor * groebnerMatrix(12,171); groebnerMatrix(39,101) = groebnerMatrix(39,101) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,40); groebnerMatrix(39,40) = 0.0; groebnerMatrix(39,62) = groebnerMatrix(39,62) - factor * groebnerMatrix(20,170); groebnerMatrix(39,158) = groebnerMatrix(39,158) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(39,41); groebnerMatrix(39,41) = 0.0; groebnerMatrix(39,65) = groebnerMatrix(39,65) - factor * groebnerMatrix(12,171); groebnerMatrix(39,102) = groebnerMatrix(39,102) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,42); groebnerMatrix(39,42) = 0.0; groebnerMatrix(39,64) = groebnerMatrix(39,64) - factor * groebnerMatrix(20,170); groebnerMatrix(39,159) = groebnerMatrix(39,159) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(39,43); groebnerMatrix(39,43) = 0.0; groebnerMatrix(39,56) = groebnerMatrix(39,56) - factor * groebnerMatrix(22,162); groebnerMatrix(39,139) = groebnerMatrix(39,139) - factor * groebnerMatrix(22,186); groebnerMatrix(39,193) = groebnerMatrix(39,193) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(39,44); groebnerMatrix(39,44) = 0.0; groebnerMatrix(39,72) = groebnerMatrix(39,72) - factor * groebnerMatrix(11,174); groebnerMatrix(39,113) = groebnerMatrix(39,113) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(39,45); groebnerMatrix(39,45) = 0.0; groebnerMatrix(39,73) = groebnerMatrix(39,73) - factor * groebnerMatrix(11,174); groebnerMatrix(39,114) = groebnerMatrix(39,114) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(39,46); groebnerMatrix(39,46) = 0.0; groebnerMatrix(39,72) = groebnerMatrix(39,72) - factor * groebnerMatrix(12,171); groebnerMatrix(39,109) = groebnerMatrix(39,109) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,47); groebnerMatrix(39,47) = 0.0; groebnerMatrix(39,71) = groebnerMatrix(39,71) - factor * groebnerMatrix(20,170); groebnerMatrix(39,161) = groebnerMatrix(39,161) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(39,48); groebnerMatrix(39,48) = 0.0; groebnerMatrix(39,52) = groebnerMatrix(39,52) - factor * groebnerMatrix(16,158); groebnerMatrix(39,169) = groebnerMatrix(39,169) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(39,49); groebnerMatrix(39,49) = 0.0; groebnerMatrix(39,75) = groebnerMatrix(39,75) - factor * groebnerMatrix(11,174); groebnerMatrix(39,116) = groebnerMatrix(39,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(39,50); groebnerMatrix(39,50) = 0.0; groebnerMatrix(39,74) = groebnerMatrix(39,74) - factor * groebnerMatrix(21,173); groebnerMatrix(39,154) = groebnerMatrix(39,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(39,51); groebnerMatrix(39,51) = 0.0; groebnerMatrix(39,77) = groebnerMatrix(39,77) - factor * groebnerMatrix(12,171); groebnerMatrix(39,114) = groebnerMatrix(39,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,52); groebnerMatrix(39,52) = 0.0; groebnerMatrix(39,76) = groebnerMatrix(39,76) - factor * groebnerMatrix(20,170); groebnerMatrix(39,162) = groebnerMatrix(39,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(39,53); groebnerMatrix(39,53) = 0.0; groebnerMatrix(39,105) = groebnerMatrix(39,105) - factor * groebnerMatrix(27,181); groebnerMatrix(39,146) = groebnerMatrix(39,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(39,54); groebnerMatrix(39,54) = 0.0; groebnerMatrix(39,80) = groebnerMatrix(39,80) - factor * groebnerMatrix(11,174); groebnerMatrix(39,117) = groebnerMatrix(39,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(39,55); groebnerMatrix(39,55) = 0.0; groebnerMatrix(39,79) = groebnerMatrix(39,79) - factor * groebnerMatrix(21,173); groebnerMatrix(39,159) = groebnerMatrix(39,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(39,56); groebnerMatrix(39,56) = 0.0; groebnerMatrix(39,115) = groebnerMatrix(39,115) - factor * groebnerMatrix(27,181); groebnerMatrix(39,158) = groebnerMatrix(39,158) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(39,57); groebnerMatrix(39,57) = 0.0; groebnerMatrix(39,90) = groebnerMatrix(39,90) - factor * groebnerMatrix(10,177); groebnerMatrix(39,134) = groebnerMatrix(39,134) - factor * groebnerMatrix(10,186); groebnerMatrix(39,188) = groebnerMatrix(39,188) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(39,58); groebnerMatrix(39,58) = 0.0; groebnerMatrix(39,91) = groebnerMatrix(39,91) - factor * groebnerMatrix(10,177); groebnerMatrix(39,135) = groebnerMatrix(39,135) - factor * groebnerMatrix(10,186); groebnerMatrix(39,189) = groebnerMatrix(39,189) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(39,59); groebnerMatrix(39,59) = 0.0; groebnerMatrix(39,93) = groebnerMatrix(39,93) - factor * groebnerMatrix(10,177); groebnerMatrix(39,137) = groebnerMatrix(39,137) - factor * groebnerMatrix(10,186); groebnerMatrix(39,191) = groebnerMatrix(39,191) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(39,60); groebnerMatrix(39,60) = 0.0; groebnerMatrix(39,94) = groebnerMatrix(39,94) - factor * groebnerMatrix(10,177); groebnerMatrix(39,138) = groebnerMatrix(39,138) - factor * groebnerMatrix(10,186); groebnerMatrix(39,192) = groebnerMatrix(39,192) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(39,61); groebnerMatrix(39,61) = 0.0; groebnerMatrix(39,63) = groebnerMatrix(39,63) - factor * groebnerMatrix(15,144); groebnerMatrix(39,66) = groebnerMatrix(39,66) - factor * groebnerMatrix(15,147); groebnerMatrix(39,194) = groebnerMatrix(39,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(39,64); groebnerMatrix(39,64) = 0.0; groebnerMatrix(39,98) = groebnerMatrix(39,98) - factor * groebnerMatrix(17,179); groebnerMatrix(39,148) = groebnerMatrix(39,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(39,65); groebnerMatrix(39,65) = 0.0; groebnerMatrix(39,99) = groebnerMatrix(39,99) - factor * groebnerMatrix(17,179); groebnerMatrix(39,149) = groebnerMatrix(39,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(39,66); groebnerMatrix(39,66) = 0.0; groebnerMatrix(39,101) = groebnerMatrix(39,101) - factor * groebnerMatrix(17,179); groebnerMatrix(39,150) = groebnerMatrix(39,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(39,67); groebnerMatrix(39,67) = 0.0; groebnerMatrix(39,72) = groebnerMatrix(39,72) - factor * groebnerMatrix(14,153); groebnerMatrix(39,78) = groebnerMatrix(39,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(39,68); groebnerMatrix(39,68) = 0.0; groebnerMatrix(39,71) = groebnerMatrix(39,71) - factor * groebnerMatrix(19,152); groebnerMatrix(39,185) = groebnerMatrix(39,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(39,69); groebnerMatrix(39,69) = 0.0; groebnerMatrix(39,104) = groebnerMatrix(39,104) - factor * groebnerMatrix(17,179); groebnerMatrix(39,151) = groebnerMatrix(39,151) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(39,70); groebnerMatrix(39,70) = 0.0; groebnerMatrix(39,75) = groebnerMatrix(39,75) - factor * groebnerMatrix(13,156); groebnerMatrix(39,81) = groebnerMatrix(39,81) - factor * groebnerMatrix(13,162); groebnerMatrix(39,194) = groebnerMatrix(39,194) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(39,73); groebnerMatrix(39,73) = 0.0; groebnerMatrix(39,77) = groebnerMatrix(39,77) - factor * groebnerMatrix(16,158); groebnerMatrix(39,176) = groebnerMatrix(39,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(39,76); groebnerMatrix(39,76) = 0.0; groebnerMatrix(39,107) = groebnerMatrix(39,107) - factor * groebnerMatrix(18,182); groebnerMatrix(39,142) = groebnerMatrix(39,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(39,77); groebnerMatrix(39,77) = 0.0; groebnerMatrix(39,108) = groebnerMatrix(39,108) - factor * groebnerMatrix(18,182); groebnerMatrix(39,143) = groebnerMatrix(39,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(39,78); groebnerMatrix(39,78) = 0.0; groebnerMatrix(39,113) = groebnerMatrix(39,113) - factor * groebnerMatrix(17,179); groebnerMatrix(39,160) = groebnerMatrix(39,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(39,79); groebnerMatrix(39,79) = 0.0; groebnerMatrix(39,110) = groebnerMatrix(39,110) - factor * groebnerMatrix(18,182); groebnerMatrix(39,148) = groebnerMatrix(39,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(39,80); groebnerMatrix(39,80) = 0.0; groebnerMatrix(39,111) = groebnerMatrix(39,111) - factor * groebnerMatrix(18,182); groebnerMatrix(39,152) = groebnerMatrix(39,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(39,81); groebnerMatrix(39,81) = 0.0; groebnerMatrix(39,116) = groebnerMatrix(39,116) - factor * groebnerMatrix(18,182); groebnerMatrix(39,157) = groebnerMatrix(39,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(39,82); groebnerMatrix(39,82) = 0.0; groebnerMatrix(39,90) = groebnerMatrix(39,90) - factor * groebnerMatrix(12,171); groebnerMatrix(39,127) = groebnerMatrix(39,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,83); groebnerMatrix(39,83) = 0.0; groebnerMatrix(39,89) = groebnerMatrix(39,89) - factor * groebnerMatrix(20,170); groebnerMatrix(39,175) = groebnerMatrix(39,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(39,84); groebnerMatrix(39,84) = 0.0; groebnerMatrix(39,119) = groebnerMatrix(39,119) - factor * groebnerMatrix(17,179); groebnerMatrix(39,166) = groebnerMatrix(39,166) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(39,85); groebnerMatrix(39,85) = 0.0; groebnerMatrix(39,93) = groebnerMatrix(39,93) - factor * groebnerMatrix(11,174); groebnerMatrix(39,130) = groebnerMatrix(39,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(39,86); groebnerMatrix(39,86) = 0.0; groebnerMatrix(39,92) = groebnerMatrix(39,92) - factor * groebnerMatrix(21,173); groebnerMatrix(39,172) = groebnerMatrix(39,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(39,87); groebnerMatrix(39,87) = 0.0; groebnerMatrix(39,122) = groebnerMatrix(39,122) - factor * groebnerMatrix(18,182); groebnerMatrix(39,163) = groebnerMatrix(39,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(39,91); groebnerMatrix(39,91) = 0.0; groebnerMatrix(39,126) = groebnerMatrix(39,126) - factor * groebnerMatrix(17,179); groebnerMatrix(39,173) = groebnerMatrix(39,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(39,94); groebnerMatrix(39,94) = 0.0; groebnerMatrix(39,129) = groebnerMatrix(39,129) - factor * groebnerMatrix(18,182); groebnerMatrix(39,170) = groebnerMatrix(39,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(39,97); groebnerMatrix(39,97) = 0.0; groebnerMatrix(39,99) = groebnerMatrix(39,99) - factor * groebnerMatrix(15,144); groebnerMatrix(39,102) = groebnerMatrix(39,102) - factor * groebnerMatrix(15,147); groebnerMatrix(39,195) = groebnerMatrix(39,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(39,100); groebnerMatrix(39,100) = 0.0; groebnerMatrix(39,115) = groebnerMatrix(39,115) - factor * groebnerMatrix(24,160); groebnerMatrix(39,139) = groebnerMatrix(39,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(39,103); groebnerMatrix(39,103) = 0.0; groebnerMatrix(39,108) = groebnerMatrix(39,108) - factor * groebnerMatrix(14,153); groebnerMatrix(39,114) = groebnerMatrix(39,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(39,104); groebnerMatrix(39,104) = 0.0; groebnerMatrix(39,107) = groebnerMatrix(39,107) - factor * groebnerMatrix(19,152); groebnerMatrix(39,186) = groebnerMatrix(39,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(39,105); groebnerMatrix(39,105) = 0.0; groebnerMatrix(39,112) = groebnerMatrix(39,112) - factor * groebnerMatrix(28,157); groebnerMatrix(39,185) = groebnerMatrix(39,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(39,106); groebnerMatrix(39,106) = 0.0; groebnerMatrix(39,111) = groebnerMatrix(39,111) - factor * groebnerMatrix(13,156); groebnerMatrix(39,117) = groebnerMatrix(39,117) - factor * groebnerMatrix(13,162); groebnerMatrix(39,195) = groebnerMatrix(39,195) - factor * groebnerMatrix(13,196); factor = -groebnerMatrix(39,109); groebnerMatrix(39,109) = 0.0; groebnerMatrix(39,113) = groebnerMatrix(39,113) - factor * groebnerMatrix(16,158); groebnerMatrix(39,184) = groebnerMatrix(39,184) - factor * groebnerMatrix(16,193); factor = groebnerMatrix(39,118); groebnerMatrix(39,118) = 0.0; groebnerMatrix(39,126) = groebnerMatrix(39,126) - factor * groebnerMatrix(12,171); groebnerMatrix(39,135) = groebnerMatrix(39,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,119); groebnerMatrix(39,119) = 0.0; groebnerMatrix(39,125) = groebnerMatrix(39,125) - factor * groebnerMatrix(20,170); groebnerMatrix(39,183) = groebnerMatrix(39,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(39,120); groebnerMatrix(39,120) = 0.0; groebnerMatrix(39,133) = groebnerMatrix(39,133) - factor * groebnerMatrix(29,178); groebnerMatrix(39,182) = groebnerMatrix(39,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(39,121); groebnerMatrix(39,121) = 0.0; groebnerMatrix(39,129) = groebnerMatrix(39,129) - factor * groebnerMatrix(11,174); groebnerMatrix(39,138) = groebnerMatrix(39,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(39,122); groebnerMatrix(39,122) = 0.0; groebnerMatrix(39,128) = groebnerMatrix(39,128) - factor * groebnerMatrix(21,173); groebnerMatrix(39,180) = groebnerMatrix(39,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(39,123); groebnerMatrix(39,123) = 0.0; groebnerMatrix(39,136) = groebnerMatrix(39,136) - factor * groebnerMatrix(27,181); groebnerMatrix(39,179) = groebnerMatrix(39,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(39,127); groebnerMatrix(39,127) = 0.0; groebnerMatrix(39,134) = groebnerMatrix(39,134) - factor * groebnerMatrix(17,179); groebnerMatrix(39,181) = groebnerMatrix(39,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(39,130); groebnerMatrix(39,130) = 0.0; groebnerMatrix(39,137) = groebnerMatrix(39,137) - factor * groebnerMatrix(18,182); groebnerMatrix(39,178) = groebnerMatrix(39,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(39,142); groebnerMatrix(39,142) = 0.0; groebnerMatrix(39,144) = groebnerMatrix(39,144) - factor * groebnerMatrix(15,144); groebnerMatrix(39,147) = groebnerMatrix(39,147) - factor * groebnerMatrix(15,147); groebnerMatrix(39,196) = groebnerMatrix(39,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(39,143); groebnerMatrix(39,143) = 0.0; groebnerMatrix(39,155) = groebnerMatrix(39,155) - factor * groebnerMatrix(26,155); groebnerMatrix(39,176) = groebnerMatrix(39,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(39,144); groebnerMatrix(39,144) = 0.0; groebnerMatrix(39,156) = groebnerMatrix(39,156) - factor * groebnerMatrix(25,156); groebnerMatrix(39,177) = groebnerMatrix(39,177) - factor * groebnerMatrix(25,177); groebnerMatrix(39,196) = groebnerMatrix(39,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(39,146); groebnerMatrix(39,146) = 0.0; groebnerMatrix(39,161) = groebnerMatrix(39,161) - factor * groebnerMatrix(23,161); groebnerMatrix(39,185) = groebnerMatrix(39,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(39,147); groebnerMatrix(39,147) = 0.0; groebnerMatrix(39,162) = groebnerMatrix(39,162) - factor * groebnerMatrix(22,162); groebnerMatrix(39,186) = groebnerMatrix(39,186) - factor * groebnerMatrix(22,186); groebnerMatrix(39,196) = groebnerMatrix(39,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(39,148); groebnerMatrix(39,148) = 0.0; groebnerMatrix(39,153) = groebnerMatrix(39,153) - factor * groebnerMatrix(14,153); groebnerMatrix(39,159) = groebnerMatrix(39,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(39,149); groebnerMatrix(39,149) = 0.0; groebnerMatrix(39,152) = groebnerMatrix(39,152) - factor * groebnerMatrix(19,152); groebnerMatrix(39,195) = groebnerMatrix(39,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(39,150); groebnerMatrix(39,150) = 0.0; groebnerMatrix(39,157) = groebnerMatrix(39,157) - factor * groebnerMatrix(28,157); groebnerMatrix(39,194) = groebnerMatrix(39,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(39,151); groebnerMatrix(39,151) = 0.0; groebnerMatrix(39,156) = groebnerMatrix(39,156) - factor * groebnerMatrix(13,156); groebnerMatrix(39,162) = groebnerMatrix(39,162) - factor * groebnerMatrix(13,162); groebnerMatrix(39,196) = groebnerMatrix(39,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,39); groebnerRow31_000000000_f(groebnerMatrix,39); factor = -groebnerMatrix(39,154); groebnerMatrix(39,154) = 0.0; groebnerMatrix(39,158) = groebnerMatrix(39,158) - factor * groebnerMatrix(16,158); groebnerMatrix(39,193) = groebnerMatrix(39,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,39); groebnerRow33_000000000_f(groebnerMatrix,39); groebnerRow34_000000000_f(groebnerMatrix,39); groebnerRow35_000000000_f(groebnerMatrix,39); groebnerRow36_000000000_f(groebnerMatrix,39); groebnerRow37_000000000_f(groebnerMatrix,39); groebnerRow38_000000000_f(groebnerMatrix,39); factor = groebnerMatrix(39,163); groebnerMatrix(39,163) = 0.0; groebnerMatrix(39,171) = groebnerMatrix(39,171) - factor * groebnerMatrix(12,171); groebnerMatrix(39,180) = groebnerMatrix(39,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(39,164); groebnerMatrix(39,164) = 0.0; groebnerMatrix(39,170) = groebnerMatrix(39,170) - factor * groebnerMatrix(20,170); groebnerMatrix(39,192) = groebnerMatrix(39,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(39,165); groebnerMatrix(39,165) = 0.0; groebnerMatrix(39,178) = groebnerMatrix(39,178) - factor * groebnerMatrix(29,178); groebnerMatrix(39,191) = groebnerMatrix(39,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(39,166); groebnerMatrix(39,166) = 0.0; groebnerMatrix(39,174) = groebnerMatrix(39,174) - factor * groebnerMatrix(11,174); groebnerMatrix(39,183) = groebnerMatrix(39,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(39,167); groebnerMatrix(39,167) = 0.0; groebnerMatrix(39,173) = groebnerMatrix(39,173) - factor * groebnerMatrix(21,173); groebnerMatrix(39,189) = groebnerMatrix(39,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(39,168); groebnerMatrix(39,168) = 0.0; groebnerMatrix(39,181) = groebnerMatrix(39,181) - factor * groebnerMatrix(27,181); groebnerMatrix(39,188) = groebnerMatrix(39,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(39,169); groebnerMatrix(39,169) = 0.0; groebnerMatrix(39,177) = groebnerMatrix(39,177) - factor * groebnerMatrix(10,177); groebnerMatrix(39,186) = groebnerMatrix(39,186) - factor * groebnerMatrix(10,186); groebnerMatrix(39,196) = groebnerMatrix(39,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(39,172); groebnerMatrix(39,172) = 0.0; groebnerMatrix(39,179) = groebnerMatrix(39,179) - factor * groebnerMatrix(17,179); groebnerMatrix(39,190) = groebnerMatrix(39,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(39,175); groebnerMatrix(39,175) = 0.0; groebnerMatrix(39,182) = groebnerMatrix(39,182) - factor * groebnerMatrix(18,182); groebnerMatrix(39,187) = groebnerMatrix(39,187) - factor * groebnerMatrix(18,187); sPolynomial40(groebnerMatrix); groebnerRow38_100000000_f(groebnerMatrix,40); groebnerRow39_100000000_f(groebnerMatrix,40); factor = groebnerMatrix(40,127); groebnerMatrix(40,127) = 0.0; groebnerMatrix(40,134) = groebnerMatrix(40,134) - factor * groebnerMatrix(17,179); groebnerMatrix(40,181) = groebnerMatrix(40,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(40,130); groebnerMatrix(40,130) = 0.0; groebnerMatrix(40,137) = groebnerMatrix(40,137) - factor * groebnerMatrix(18,182); groebnerMatrix(40,178) = groebnerMatrix(40,178) - factor * groebnerMatrix(18,187); groebnerRow34_000000000_f(groebnerMatrix,40); groebnerRow35_000000000_f(groebnerMatrix,40); groebnerRow36_000000000_f(groebnerMatrix,40); groebnerRow37_000000000_f(groebnerMatrix,40); groebnerRow38_000000000_f(groebnerMatrix,40); groebnerRow39_000000000_f(groebnerMatrix,40); factor = groebnerMatrix(40,172); groebnerMatrix(40,172) = 0.0; groebnerMatrix(40,179) = groebnerMatrix(40,179) - factor * groebnerMatrix(17,179); groebnerMatrix(40,190) = groebnerMatrix(40,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(40,175); groebnerMatrix(40,175) = 0.0; groebnerMatrix(40,182) = groebnerMatrix(40,182) - factor * groebnerMatrix(18,182); groebnerMatrix(40,187) = groebnerMatrix(40,187) - factor * groebnerMatrix(18,187); sPolynomial41(groebnerMatrix); factor = -groebnerMatrix(41,81); groebnerMatrix(41,81) = 0.0; groebnerMatrix(41,116) = groebnerMatrix(41,116) - factor * groebnerMatrix(18,182); groebnerMatrix(41,157) = groebnerMatrix(41,157) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,41); groebnerRow33_100000000_f(groebnerMatrix,41); groebnerRow34_100000000_f(groebnerMatrix,41); groebnerRow35_100000000_f(groebnerMatrix,41); groebnerRow36_100000000_f(groebnerMatrix,41); groebnerRow37_100000000_f(groebnerMatrix,41); groebnerRow38_100000000_f(groebnerMatrix,41); groebnerRow39_100000000_f(groebnerMatrix,41); factor = groebnerMatrix(41,127); groebnerMatrix(41,127) = 0.0; groebnerMatrix(41,134) = groebnerMatrix(41,134) - factor * groebnerMatrix(17,179); groebnerMatrix(41,181) = groebnerMatrix(41,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(41,130); groebnerMatrix(41,130) = 0.0; groebnerMatrix(41,137) = groebnerMatrix(41,137) - factor * groebnerMatrix(18,182); groebnerMatrix(41,178) = groebnerMatrix(41,178) - factor * groebnerMatrix(18,187); groebnerRow30_000000000_f(groebnerMatrix,41); groebnerRow31_000000000_f(groebnerMatrix,41); groebnerRow32_000000000_f(groebnerMatrix,41); groebnerRow33_000000000_f(groebnerMatrix,41); groebnerRow34_000000000_f(groebnerMatrix,41); groebnerRow35_000000000_f(groebnerMatrix,41); groebnerRow36_000000000_f(groebnerMatrix,41); groebnerRow37_000000000_f(groebnerMatrix,41); groebnerRow38_000000000_f(groebnerMatrix,41); groebnerRow39_000000000_f(groebnerMatrix,41); factor = groebnerMatrix(41,172); groebnerMatrix(41,172) = 0.0; groebnerMatrix(41,179) = groebnerMatrix(41,179) - factor * groebnerMatrix(17,179); groebnerMatrix(41,190) = groebnerMatrix(41,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(41,175); groebnerMatrix(41,175) = 0.0; groebnerMatrix(41,182) = groebnerMatrix(41,182) - factor * groebnerMatrix(18,182); groebnerMatrix(41,187) = groebnerMatrix(41,187) - factor * groebnerMatrix(18,187); sPolynomial42(groebnerMatrix); factor = -groebnerMatrix(42,80); groebnerMatrix(42,80) = 0.0; groebnerMatrix(42,111) = groebnerMatrix(42,111) - factor * groebnerMatrix(18,182); groebnerMatrix(42,152) = groebnerMatrix(42,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(42,81); groebnerMatrix(42,81) = 0.0; groebnerMatrix(42,116) = groebnerMatrix(42,116) - factor * groebnerMatrix(18,182); groebnerMatrix(42,157) = groebnerMatrix(42,157) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,42); groebnerRow41_000000000_f(groebnerMatrix,42); groebnerRow32_100000000_f(groebnerMatrix,42); groebnerRow33_100000000_f(groebnerMatrix,42); groebnerRow34_100000000_f(groebnerMatrix,42); groebnerRow35_100000000_f(groebnerMatrix,42); groebnerRow36_100000000_f(groebnerMatrix,42); groebnerRow37_100000000_f(groebnerMatrix,42); groebnerRow38_100000000_f(groebnerMatrix,42); groebnerRow39_100000000_f(groebnerMatrix,42); factor = groebnerMatrix(42,127); groebnerMatrix(42,127) = 0.0; groebnerMatrix(42,134) = groebnerMatrix(42,134) - factor * groebnerMatrix(17,179); groebnerMatrix(42,181) = groebnerMatrix(42,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(42,130); groebnerMatrix(42,130) = 0.0; groebnerMatrix(42,137) = groebnerMatrix(42,137) - factor * groebnerMatrix(18,182); groebnerMatrix(42,178) = groebnerMatrix(42,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(42,148); groebnerMatrix(42,148) = 0.0; groebnerMatrix(42,153) = groebnerMatrix(42,153) - factor * groebnerMatrix(14,153); groebnerMatrix(42,159) = groebnerMatrix(42,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,42); groebnerRow31_000000000_f(groebnerMatrix,42); groebnerRow32_000000000_f(groebnerMatrix,42); groebnerRow33_000000000_f(groebnerMatrix,42); groebnerRow34_000000000_f(groebnerMatrix,42); groebnerRow35_000000000_f(groebnerMatrix,42); groebnerRow36_000000000_f(groebnerMatrix,42); groebnerRow37_000000000_f(groebnerMatrix,42); groebnerRow38_000000000_f(groebnerMatrix,42); groebnerRow39_000000000_f(groebnerMatrix,42); factor = groebnerMatrix(42,172); groebnerMatrix(42,172) = 0.0; groebnerMatrix(42,179) = groebnerMatrix(42,179) - factor * groebnerMatrix(17,179); groebnerMatrix(42,190) = groebnerMatrix(42,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(42,175); groebnerMatrix(42,175) = 0.0; groebnerMatrix(42,182) = groebnerMatrix(42,182) - factor * groebnerMatrix(18,182); groebnerMatrix(42,187) = groebnerMatrix(42,187) - factor * groebnerMatrix(18,187); sPolynomial43(groebnerMatrix); factor = -groebnerMatrix(43,79); groebnerMatrix(43,79) = 0.0; groebnerMatrix(43,110) = groebnerMatrix(43,110) - factor * groebnerMatrix(18,182); groebnerMatrix(43,148) = groebnerMatrix(43,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(43,80); groebnerMatrix(43,80) = 0.0; groebnerMatrix(43,111) = groebnerMatrix(43,111) - factor * groebnerMatrix(18,182); groebnerMatrix(43,152) = groebnerMatrix(43,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(43,81); groebnerMatrix(43,81) = 0.0; groebnerMatrix(43,116) = groebnerMatrix(43,116) - factor * groebnerMatrix(18,182); groebnerMatrix(43,157) = groebnerMatrix(43,157) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,43); groebnerRow41_000000000_f(groebnerMatrix,43); groebnerRow42_000000000_f(groebnerMatrix,43); groebnerRow32_100000000_f(groebnerMatrix,43); groebnerRow33_100000000_f(groebnerMatrix,43); groebnerRow34_100000000_f(groebnerMatrix,43); groebnerRow35_100000000_f(groebnerMatrix,43); groebnerRow36_100000000_f(groebnerMatrix,43); groebnerRow37_100000000_f(groebnerMatrix,43); groebnerRow38_100000000_f(groebnerMatrix,43); groebnerRow39_100000000_f(groebnerMatrix,43); factor = groebnerMatrix(43,127); groebnerMatrix(43,127) = 0.0; groebnerMatrix(43,134) = groebnerMatrix(43,134) - factor * groebnerMatrix(17,179); groebnerMatrix(43,181) = groebnerMatrix(43,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(43,130); groebnerMatrix(43,130) = 0.0; groebnerMatrix(43,137) = groebnerMatrix(43,137) - factor * groebnerMatrix(18,182); groebnerMatrix(43,178) = groebnerMatrix(43,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(43,148); groebnerMatrix(43,148) = 0.0; groebnerMatrix(43,153) = groebnerMatrix(43,153) - factor * groebnerMatrix(14,153); groebnerMatrix(43,159) = groebnerMatrix(43,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,43); groebnerRow31_000000000_f(groebnerMatrix,43); groebnerRow32_000000000_f(groebnerMatrix,43); groebnerRow33_000000000_f(groebnerMatrix,43); groebnerRow34_000000000_f(groebnerMatrix,43); groebnerRow35_000000000_f(groebnerMatrix,43); groebnerRow36_000000000_f(groebnerMatrix,43); groebnerRow37_000000000_f(groebnerMatrix,43); groebnerRow38_000000000_f(groebnerMatrix,43); groebnerRow39_000000000_f(groebnerMatrix,43); factor = groebnerMatrix(43,172); groebnerMatrix(43,172) = 0.0; groebnerMatrix(43,179) = groebnerMatrix(43,179) - factor * groebnerMatrix(17,179); groebnerMatrix(43,190) = groebnerMatrix(43,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(43,175); groebnerMatrix(43,175) = 0.0; groebnerMatrix(43,182) = groebnerMatrix(43,182) - factor * groebnerMatrix(18,182); groebnerMatrix(43,187) = groebnerMatrix(43,187) - factor * groebnerMatrix(18,187); sPolynomial44(groebnerMatrix); factor = groebnerMatrix(44,78); groebnerMatrix(44,78) = 0.0; groebnerMatrix(44,113) = groebnerMatrix(44,113) - factor * groebnerMatrix(17,179); groebnerMatrix(44,160) = groebnerMatrix(44,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(44,79); groebnerMatrix(44,79) = 0.0; groebnerMatrix(44,110) = groebnerMatrix(44,110) - factor * groebnerMatrix(18,182); groebnerMatrix(44,148) = groebnerMatrix(44,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(44,80); groebnerMatrix(44,80) = 0.0; groebnerMatrix(44,111) = groebnerMatrix(44,111) - factor * groebnerMatrix(18,182); groebnerMatrix(44,152) = groebnerMatrix(44,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(44,81); groebnerMatrix(44,81) = 0.0; groebnerMatrix(44,116) = groebnerMatrix(44,116) - factor * groebnerMatrix(18,182); groebnerMatrix(44,157) = groebnerMatrix(44,157) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,44); groebnerRow41_000000000_f(groebnerMatrix,44); groebnerRow42_000000000_f(groebnerMatrix,44); groebnerRow43_000000000_f(groebnerMatrix,44); groebnerRow31_100000000_f(groebnerMatrix,44); groebnerRow32_100000000_f(groebnerMatrix,44); groebnerRow33_100000000_f(groebnerMatrix,44); groebnerRow34_100000000_f(groebnerMatrix,44); groebnerRow35_100000000_f(groebnerMatrix,44); groebnerRow36_100000000_f(groebnerMatrix,44); groebnerRow37_100000000_f(groebnerMatrix,44); groebnerRow38_100000000_f(groebnerMatrix,44); groebnerRow39_100000000_f(groebnerMatrix,44); factor = groebnerMatrix(44,127); groebnerMatrix(44,127) = 0.0; groebnerMatrix(44,134) = groebnerMatrix(44,134) - factor * groebnerMatrix(17,179); groebnerMatrix(44,181) = groebnerMatrix(44,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(44,130); groebnerMatrix(44,130) = 0.0; groebnerMatrix(44,137) = groebnerMatrix(44,137) - factor * groebnerMatrix(18,182); groebnerMatrix(44,178) = groebnerMatrix(44,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(44,143); groebnerMatrix(44,143) = 0.0; groebnerMatrix(44,155) = groebnerMatrix(44,155) - factor * groebnerMatrix(26,155); groebnerMatrix(44,176) = groebnerMatrix(44,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(44,148); groebnerMatrix(44,148) = 0.0; groebnerMatrix(44,153) = groebnerMatrix(44,153) - factor * groebnerMatrix(14,153); groebnerMatrix(44,159) = groebnerMatrix(44,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,44); groebnerRow31_000000000_f(groebnerMatrix,44); groebnerRow32_000000000_f(groebnerMatrix,44); groebnerRow33_000000000_f(groebnerMatrix,44); groebnerRow34_000000000_f(groebnerMatrix,44); groebnerRow35_000000000_f(groebnerMatrix,44); groebnerRow36_000000000_f(groebnerMatrix,44); groebnerRow37_000000000_f(groebnerMatrix,44); groebnerRow38_000000000_f(groebnerMatrix,44); groebnerRow39_000000000_f(groebnerMatrix,44); factor = groebnerMatrix(44,172); groebnerMatrix(44,172) = 0.0; groebnerMatrix(44,179) = groebnerMatrix(44,179) - factor * groebnerMatrix(17,179); groebnerMatrix(44,190) = groebnerMatrix(44,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(44,175); groebnerMatrix(44,175) = 0.0; groebnerMatrix(44,182) = groebnerMatrix(44,182) - factor * groebnerMatrix(18,182); groebnerMatrix(44,187) = groebnerMatrix(44,187) - factor * groebnerMatrix(18,187); sPolynomial45(groebnerMatrix); factor = -groebnerMatrix(45,77); groebnerMatrix(45,77) = 0.0; groebnerMatrix(45,108) = groebnerMatrix(45,108) - factor * groebnerMatrix(18,182); groebnerMatrix(45,143) = groebnerMatrix(45,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(45,78); groebnerMatrix(45,78) = 0.0; groebnerMatrix(45,113) = groebnerMatrix(45,113) - factor * groebnerMatrix(17,179); groebnerMatrix(45,160) = groebnerMatrix(45,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(45,79); groebnerMatrix(45,79) = 0.0; groebnerMatrix(45,110) = groebnerMatrix(45,110) - factor * groebnerMatrix(18,182); groebnerMatrix(45,148) = groebnerMatrix(45,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(45,80); groebnerMatrix(45,80) = 0.0; groebnerMatrix(45,111) = groebnerMatrix(45,111) - factor * groebnerMatrix(18,182); groebnerMatrix(45,152) = groebnerMatrix(45,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(45,81); groebnerMatrix(45,81) = 0.0; groebnerMatrix(45,116) = groebnerMatrix(45,116) - factor * groebnerMatrix(18,182); groebnerMatrix(45,157) = groebnerMatrix(45,157) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,45); groebnerRow41_000000000_f(groebnerMatrix,45); groebnerRow42_000000000_f(groebnerMatrix,45); groebnerRow43_000000000_f(groebnerMatrix,45); groebnerRow44_000000000_f(groebnerMatrix,45); groebnerRow30_100000000_f(groebnerMatrix,45); groebnerRow31_100000000_f(groebnerMatrix,45); groebnerRow32_100000000_f(groebnerMatrix,45); groebnerRow33_100000000_f(groebnerMatrix,45); groebnerRow34_100000000_f(groebnerMatrix,45); groebnerRow35_100000000_f(groebnerMatrix,45); groebnerRow36_100000000_f(groebnerMatrix,45); groebnerRow37_100000000_f(groebnerMatrix,45); groebnerRow38_100000000_f(groebnerMatrix,45); groebnerRow39_100000000_f(groebnerMatrix,45); factor = groebnerMatrix(45,127); groebnerMatrix(45,127) = 0.0; groebnerMatrix(45,134) = groebnerMatrix(45,134) - factor * groebnerMatrix(17,179); groebnerMatrix(45,181) = groebnerMatrix(45,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(45,130); groebnerMatrix(45,130) = 0.0; groebnerMatrix(45,137) = groebnerMatrix(45,137) - factor * groebnerMatrix(18,182); groebnerMatrix(45,178) = groebnerMatrix(45,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(45,142); groebnerMatrix(45,142) = 0.0; groebnerMatrix(45,144) = groebnerMatrix(45,144) - factor * groebnerMatrix(15,144); groebnerMatrix(45,147) = groebnerMatrix(45,147) - factor * groebnerMatrix(15,147); groebnerMatrix(45,196) = groebnerMatrix(45,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(45,143); groebnerMatrix(45,143) = 0.0; groebnerMatrix(45,155) = groebnerMatrix(45,155) - factor * groebnerMatrix(26,155); groebnerMatrix(45,176) = groebnerMatrix(45,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(45,144); groebnerMatrix(45,144) = 0.0; groebnerMatrix(45,156) = groebnerMatrix(45,156) - factor * groebnerMatrix(25,156); groebnerMatrix(45,177) = groebnerMatrix(45,177) - factor * groebnerMatrix(25,177); groebnerMatrix(45,196) = groebnerMatrix(45,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(45,147); groebnerMatrix(45,147) = 0.0; groebnerMatrix(45,162) = groebnerMatrix(45,162) - factor * groebnerMatrix(22,162); groebnerMatrix(45,186) = groebnerMatrix(45,186) - factor * groebnerMatrix(22,186); groebnerMatrix(45,196) = groebnerMatrix(45,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(45,148); groebnerMatrix(45,148) = 0.0; groebnerMatrix(45,153) = groebnerMatrix(45,153) - factor * groebnerMatrix(14,153); groebnerMatrix(45,159) = groebnerMatrix(45,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,45); groebnerRow31_000000000_f(groebnerMatrix,45); groebnerRow32_000000000_f(groebnerMatrix,45); groebnerRow33_000000000_f(groebnerMatrix,45); groebnerRow34_000000000_f(groebnerMatrix,45); groebnerRow35_000000000_f(groebnerMatrix,45); groebnerRow36_000000000_f(groebnerMatrix,45); groebnerRow37_000000000_f(groebnerMatrix,45); groebnerRow38_000000000_f(groebnerMatrix,45); groebnerRow39_000000000_f(groebnerMatrix,45); factor = groebnerMatrix(45,172); groebnerMatrix(45,172) = 0.0; groebnerMatrix(45,179) = groebnerMatrix(45,179) - factor * groebnerMatrix(17,179); groebnerMatrix(45,190) = groebnerMatrix(45,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(45,175); groebnerMatrix(45,175) = 0.0; groebnerMatrix(45,182) = groebnerMatrix(45,182) - factor * groebnerMatrix(18,182); groebnerMatrix(45,187) = groebnerMatrix(45,187) - factor * groebnerMatrix(18,187); sPolynomial46(groebnerMatrix); factor = groebnerMatrix(46,82); groebnerMatrix(46,82) = 0.0; groebnerMatrix(46,90) = groebnerMatrix(46,90) - factor * groebnerMatrix(12,171); groebnerMatrix(46,127) = groebnerMatrix(46,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(46,83); groebnerMatrix(46,83) = 0.0; groebnerMatrix(46,89) = groebnerMatrix(46,89) - factor * groebnerMatrix(20,170); groebnerMatrix(46,175) = groebnerMatrix(46,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(46,85); groebnerMatrix(46,85) = 0.0; groebnerMatrix(46,93) = groebnerMatrix(46,93) - factor * groebnerMatrix(11,174); groebnerMatrix(46,130) = groebnerMatrix(46,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(46,86); groebnerMatrix(46,86) = 0.0; groebnerMatrix(46,92) = groebnerMatrix(46,92) - factor * groebnerMatrix(21,173); groebnerMatrix(46,172) = groebnerMatrix(46,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(46,88); groebnerMatrix(46,88) = 0.0; groebnerMatrix(46,96) = groebnerMatrix(46,96) - factor * groebnerMatrix(10,177); groebnerMatrix(46,140) = groebnerMatrix(46,140) - factor * groebnerMatrix(10,186); groebnerMatrix(46,194) = groebnerMatrix(46,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,46); groebnerRow41_000000000_f(groebnerMatrix,46); groebnerRow42_000000000_f(groebnerMatrix,46); groebnerRow43_000000000_f(groebnerMatrix,46); groebnerRow44_000000000_f(groebnerMatrix,46); groebnerRow45_000000000_f(groebnerMatrix,46); groebnerRow37_100000000_f(groebnerMatrix,46); groebnerRow38_100000000_f(groebnerMatrix,46); groebnerRow39_100000000_f(groebnerMatrix,46); factor = groebnerMatrix(46,118); groebnerMatrix(46,118) = 0.0; groebnerMatrix(46,126) = groebnerMatrix(46,126) - factor * groebnerMatrix(12,171); groebnerMatrix(46,135) = groebnerMatrix(46,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(46,119); groebnerMatrix(46,119) = 0.0; groebnerMatrix(46,125) = groebnerMatrix(46,125) - factor * groebnerMatrix(20,170); groebnerMatrix(46,183) = groebnerMatrix(46,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(46,120); groebnerMatrix(46,120) = 0.0; groebnerMatrix(46,133) = groebnerMatrix(46,133) - factor * groebnerMatrix(29,178); groebnerMatrix(46,182) = groebnerMatrix(46,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(46,121); groebnerMatrix(46,121) = 0.0; groebnerMatrix(46,129) = groebnerMatrix(46,129) - factor * groebnerMatrix(11,174); groebnerMatrix(46,138) = groebnerMatrix(46,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(46,122); groebnerMatrix(46,122) = 0.0; groebnerMatrix(46,128) = groebnerMatrix(46,128) - factor * groebnerMatrix(21,173); groebnerMatrix(46,180) = groebnerMatrix(46,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(46,123); groebnerMatrix(46,123) = 0.0; groebnerMatrix(46,136) = groebnerMatrix(46,136) - factor * groebnerMatrix(27,181); groebnerMatrix(46,179) = groebnerMatrix(46,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(46,124); groebnerMatrix(46,124) = 0.0; groebnerMatrix(46,132) = groebnerMatrix(46,132) - factor * groebnerMatrix(10,177); groebnerMatrix(46,141) = groebnerMatrix(46,141) - factor * groebnerMatrix(10,186); groebnerMatrix(46,195) = groebnerMatrix(46,195) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(46,127); groebnerMatrix(46,127) = 0.0; groebnerMatrix(46,134) = groebnerMatrix(46,134) - factor * groebnerMatrix(17,179); groebnerMatrix(46,181) = groebnerMatrix(46,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(46,130); groebnerMatrix(46,130) = 0.0; groebnerMatrix(46,137) = groebnerMatrix(46,137) - factor * groebnerMatrix(18,182); groebnerMatrix(46,178) = groebnerMatrix(46,178) - factor * groebnerMatrix(18,187); groebnerRow35_000000000_f(groebnerMatrix,46); groebnerRow36_000000000_f(groebnerMatrix,46); groebnerRow37_000000000_f(groebnerMatrix,46); groebnerRow38_000000000_f(groebnerMatrix,46); groebnerRow39_000000000_f(groebnerMatrix,46); factor = groebnerMatrix(46,163); groebnerMatrix(46,163) = 0.0; groebnerMatrix(46,171) = groebnerMatrix(46,171) - factor * groebnerMatrix(12,171); groebnerMatrix(46,180) = groebnerMatrix(46,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(46,164); groebnerMatrix(46,164) = 0.0; groebnerMatrix(46,170) = groebnerMatrix(46,170) - factor * groebnerMatrix(20,170); groebnerMatrix(46,192) = groebnerMatrix(46,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(46,165); groebnerMatrix(46,165) = 0.0; groebnerMatrix(46,178) = groebnerMatrix(46,178) - factor * groebnerMatrix(29,178); groebnerMatrix(46,191) = groebnerMatrix(46,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(46,166); groebnerMatrix(46,166) = 0.0; groebnerMatrix(46,174) = groebnerMatrix(46,174) - factor * groebnerMatrix(11,174); groebnerMatrix(46,183) = groebnerMatrix(46,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(46,167); groebnerMatrix(46,167) = 0.0; groebnerMatrix(46,173) = groebnerMatrix(46,173) - factor * groebnerMatrix(21,173); groebnerMatrix(46,189) = groebnerMatrix(46,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(46,168); groebnerMatrix(46,168) = 0.0; groebnerMatrix(46,181) = groebnerMatrix(46,181) - factor * groebnerMatrix(27,181); groebnerMatrix(46,188) = groebnerMatrix(46,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(46,169); groebnerMatrix(46,169) = 0.0; groebnerMatrix(46,177) = groebnerMatrix(46,177) - factor * groebnerMatrix(10,177); groebnerMatrix(46,186) = groebnerMatrix(46,186) - factor * groebnerMatrix(10,186); groebnerMatrix(46,196) = groebnerMatrix(46,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(46,172); groebnerMatrix(46,172) = 0.0; groebnerMatrix(46,179) = groebnerMatrix(46,179) - factor * groebnerMatrix(17,179); groebnerMatrix(46,190) = groebnerMatrix(46,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(46,175); groebnerMatrix(46,175) = 0.0; groebnerMatrix(46,182) = groebnerMatrix(46,182) - factor * groebnerMatrix(18,182); groebnerMatrix(46,187) = groebnerMatrix(46,187) - factor * groebnerMatrix(18,187); sPolynomial47(groebnerMatrix); factor = groebnerMatrix(47,56); groebnerMatrix(47,56) = 0.0; groebnerMatrix(47,115) = groebnerMatrix(47,115) - factor * groebnerMatrix(27,181); groebnerMatrix(47,158) = groebnerMatrix(47,158) - factor * groebnerMatrix(27,188); factor = -groebnerMatrix(47,79); groebnerMatrix(47,79) = 0.0; groebnerMatrix(47,110) = groebnerMatrix(47,110) - factor * groebnerMatrix(18,182); groebnerMatrix(47,148) = groebnerMatrix(47,148) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(47,82); groebnerMatrix(47,82) = 0.0; groebnerMatrix(47,90) = groebnerMatrix(47,90) - factor * groebnerMatrix(12,171); groebnerMatrix(47,127) = groebnerMatrix(47,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(47,83); groebnerMatrix(47,83) = 0.0; groebnerMatrix(47,89) = groebnerMatrix(47,89) - factor * groebnerMatrix(20,170); groebnerMatrix(47,175) = groebnerMatrix(47,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(47,85); groebnerMatrix(47,85) = 0.0; groebnerMatrix(47,93) = groebnerMatrix(47,93) - factor * groebnerMatrix(11,174); groebnerMatrix(47,130) = groebnerMatrix(47,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(47,86); groebnerMatrix(47,86) = 0.0; groebnerMatrix(47,92) = groebnerMatrix(47,92) - factor * groebnerMatrix(21,173); groebnerMatrix(47,172) = groebnerMatrix(47,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(47,88); groebnerMatrix(47,88) = 0.0; groebnerMatrix(47,96) = groebnerMatrix(47,96) - factor * groebnerMatrix(10,177); groebnerMatrix(47,140) = groebnerMatrix(47,140) - factor * groebnerMatrix(10,186); groebnerMatrix(47,194) = groebnerMatrix(47,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,47); groebnerRow41_000000000_f(groebnerMatrix,47); groebnerRow42_000000000_f(groebnerMatrix,47); groebnerRow43_000000000_f(groebnerMatrix,47); groebnerRow44_000000000_f(groebnerMatrix,47); groebnerRow45_000000000_f(groebnerMatrix,47); groebnerRow32_100000000_f(groebnerMatrix,47); groebnerRow33_100000000_f(groebnerMatrix,47); groebnerRow34_100000000_f(groebnerMatrix,47); groebnerRow35_100000000_f(groebnerMatrix,47); groebnerRow36_100000000_f(groebnerMatrix,47); groebnerRow37_100000000_f(groebnerMatrix,47); groebnerRow38_100000000_f(groebnerMatrix,47); groebnerRow39_100000000_f(groebnerMatrix,47); factor = groebnerMatrix(47,118); groebnerMatrix(47,118) = 0.0; groebnerMatrix(47,126) = groebnerMatrix(47,126) - factor * groebnerMatrix(12,171); groebnerMatrix(47,135) = groebnerMatrix(47,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(47,119); groebnerMatrix(47,119) = 0.0; groebnerMatrix(47,125) = groebnerMatrix(47,125) - factor * groebnerMatrix(20,170); groebnerMatrix(47,183) = groebnerMatrix(47,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(47,120); groebnerMatrix(47,120) = 0.0; groebnerMatrix(47,133) = groebnerMatrix(47,133) - factor * groebnerMatrix(29,178); groebnerMatrix(47,182) = groebnerMatrix(47,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(47,121); groebnerMatrix(47,121) = 0.0; groebnerMatrix(47,129) = groebnerMatrix(47,129) - factor * groebnerMatrix(11,174); groebnerMatrix(47,138) = groebnerMatrix(47,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(47,122); groebnerMatrix(47,122) = 0.0; groebnerMatrix(47,128) = groebnerMatrix(47,128) - factor * groebnerMatrix(21,173); groebnerMatrix(47,180) = groebnerMatrix(47,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(47,123); groebnerMatrix(47,123) = 0.0; groebnerMatrix(47,136) = groebnerMatrix(47,136) - factor * groebnerMatrix(27,181); groebnerMatrix(47,179) = groebnerMatrix(47,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(47,124); groebnerMatrix(47,124) = 0.0; groebnerMatrix(47,132) = groebnerMatrix(47,132) - factor * groebnerMatrix(10,177); groebnerMatrix(47,141) = groebnerMatrix(47,141) - factor * groebnerMatrix(10,186); groebnerMatrix(47,195) = groebnerMatrix(47,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,47); factor = groebnerMatrix(47,127); groebnerMatrix(47,127) = 0.0; groebnerMatrix(47,134) = groebnerMatrix(47,134) - factor * groebnerMatrix(17,179); groebnerMatrix(47,181) = groebnerMatrix(47,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(47,130); groebnerMatrix(47,130) = 0.0; groebnerMatrix(47,137) = groebnerMatrix(47,137) - factor * groebnerMatrix(18,182); groebnerMatrix(47,178) = groebnerMatrix(47,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(47,148); groebnerMatrix(47,148) = 0.0; groebnerMatrix(47,153) = groebnerMatrix(47,153) - factor * groebnerMatrix(14,153); groebnerMatrix(47,159) = groebnerMatrix(47,159) - factor * groebnerMatrix(14,159); groebnerRow31_000000000_f(groebnerMatrix,47); groebnerRow32_000000000_f(groebnerMatrix,47); groebnerRow33_000000000_f(groebnerMatrix,47); groebnerRow34_000000000_f(groebnerMatrix,47); groebnerRow35_000000000_f(groebnerMatrix,47); groebnerRow36_000000000_f(groebnerMatrix,47); groebnerRow37_000000000_f(groebnerMatrix,47); groebnerRow38_000000000_f(groebnerMatrix,47); groebnerRow39_000000000_f(groebnerMatrix,47); factor = groebnerMatrix(47,163); groebnerMatrix(47,163) = 0.0; groebnerMatrix(47,171) = groebnerMatrix(47,171) - factor * groebnerMatrix(12,171); groebnerMatrix(47,180) = groebnerMatrix(47,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(47,164); groebnerMatrix(47,164) = 0.0; groebnerMatrix(47,170) = groebnerMatrix(47,170) - factor * groebnerMatrix(20,170); groebnerMatrix(47,192) = groebnerMatrix(47,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(47,165); groebnerMatrix(47,165) = 0.0; groebnerMatrix(47,178) = groebnerMatrix(47,178) - factor * groebnerMatrix(29,178); groebnerMatrix(47,191) = groebnerMatrix(47,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(47,166); groebnerMatrix(47,166) = 0.0; groebnerMatrix(47,174) = groebnerMatrix(47,174) - factor * groebnerMatrix(11,174); groebnerMatrix(47,183) = groebnerMatrix(47,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(47,167); groebnerMatrix(47,167) = 0.0; groebnerMatrix(47,173) = groebnerMatrix(47,173) - factor * groebnerMatrix(21,173); groebnerMatrix(47,189) = groebnerMatrix(47,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(47,168); groebnerMatrix(47,168) = 0.0; groebnerMatrix(47,181) = groebnerMatrix(47,181) - factor * groebnerMatrix(27,181); groebnerMatrix(47,188) = groebnerMatrix(47,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(47,169); groebnerMatrix(47,169) = 0.0; groebnerMatrix(47,177) = groebnerMatrix(47,177) - factor * groebnerMatrix(10,177); groebnerMatrix(47,186) = groebnerMatrix(47,186) - factor * groebnerMatrix(10,186); groebnerMatrix(47,196) = groebnerMatrix(47,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(47,172); groebnerMatrix(47,172) = 0.0; groebnerMatrix(47,179) = groebnerMatrix(47,179) - factor * groebnerMatrix(17,179); groebnerMatrix(47,190) = groebnerMatrix(47,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(47,175); groebnerMatrix(47,175) = 0.0; groebnerMatrix(47,182) = groebnerMatrix(47,182) - factor * groebnerMatrix(18,182); groebnerMatrix(47,187) = groebnerMatrix(47,187) - factor * groebnerMatrix(18,187); sPolynomial48(groebnerMatrix); factor = -groebnerMatrix(48,55); groebnerMatrix(48,55) = 0.0; groebnerMatrix(48,79) = groebnerMatrix(48,79) - factor * groebnerMatrix(21,173); groebnerMatrix(48,159) = groebnerMatrix(48,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(48,56); groebnerMatrix(48,56) = 0.0; groebnerMatrix(48,115) = groebnerMatrix(48,115) - factor * groebnerMatrix(27,181); groebnerMatrix(48,158) = groebnerMatrix(48,158) - factor * groebnerMatrix(27,188); factor = -groebnerMatrix(48,79); groebnerMatrix(48,79) = 0.0; groebnerMatrix(48,110) = groebnerMatrix(48,110) - factor * groebnerMatrix(18,182); groebnerMatrix(48,148) = groebnerMatrix(48,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(48,80); groebnerMatrix(48,80) = 0.0; groebnerMatrix(48,111) = groebnerMatrix(48,111) - factor * groebnerMatrix(18,182); groebnerMatrix(48,152) = groebnerMatrix(48,152) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(48,82); groebnerMatrix(48,82) = 0.0; groebnerMatrix(48,90) = groebnerMatrix(48,90) - factor * groebnerMatrix(12,171); groebnerMatrix(48,127) = groebnerMatrix(48,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(48,83); groebnerMatrix(48,83) = 0.0; groebnerMatrix(48,89) = groebnerMatrix(48,89) - factor * groebnerMatrix(20,170); groebnerMatrix(48,175) = groebnerMatrix(48,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(48,85); groebnerMatrix(48,85) = 0.0; groebnerMatrix(48,93) = groebnerMatrix(48,93) - factor * groebnerMatrix(11,174); groebnerMatrix(48,130) = groebnerMatrix(48,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(48,86); groebnerMatrix(48,86) = 0.0; groebnerMatrix(48,92) = groebnerMatrix(48,92) - factor * groebnerMatrix(21,173); groebnerMatrix(48,172) = groebnerMatrix(48,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(48,88); groebnerMatrix(48,88) = 0.0; groebnerMatrix(48,96) = groebnerMatrix(48,96) - factor * groebnerMatrix(10,177); groebnerMatrix(48,140) = groebnerMatrix(48,140) - factor * groebnerMatrix(10,186); groebnerMatrix(48,194) = groebnerMatrix(48,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,48); groebnerRow41_000000000_f(groebnerMatrix,48); groebnerRow42_000000000_f(groebnerMatrix,48); groebnerRow43_000000000_f(groebnerMatrix,48); groebnerRow44_000000000_f(groebnerMatrix,48); groebnerRow45_000000000_f(groebnerMatrix,48); groebnerRow32_100000000_f(groebnerMatrix,48); groebnerRow33_100000000_f(groebnerMatrix,48); groebnerRow34_100000000_f(groebnerMatrix,48); groebnerRow35_100000000_f(groebnerMatrix,48); groebnerRow36_100000000_f(groebnerMatrix,48); groebnerRow37_100000000_f(groebnerMatrix,48); groebnerRow38_100000000_f(groebnerMatrix,48); groebnerRow39_100000000_f(groebnerMatrix,48); factor = groebnerMatrix(48,118); groebnerMatrix(48,118) = 0.0; groebnerMatrix(48,126) = groebnerMatrix(48,126) - factor * groebnerMatrix(12,171); groebnerMatrix(48,135) = groebnerMatrix(48,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(48,119); groebnerMatrix(48,119) = 0.0; groebnerMatrix(48,125) = groebnerMatrix(48,125) - factor * groebnerMatrix(20,170); groebnerMatrix(48,183) = groebnerMatrix(48,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(48,120); groebnerMatrix(48,120) = 0.0; groebnerMatrix(48,133) = groebnerMatrix(48,133) - factor * groebnerMatrix(29,178); groebnerMatrix(48,182) = groebnerMatrix(48,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(48,121); groebnerMatrix(48,121) = 0.0; groebnerMatrix(48,129) = groebnerMatrix(48,129) - factor * groebnerMatrix(11,174); groebnerMatrix(48,138) = groebnerMatrix(48,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(48,122); groebnerMatrix(48,122) = 0.0; groebnerMatrix(48,128) = groebnerMatrix(48,128) - factor * groebnerMatrix(21,173); groebnerMatrix(48,180) = groebnerMatrix(48,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(48,123); groebnerMatrix(48,123) = 0.0; groebnerMatrix(48,136) = groebnerMatrix(48,136) - factor * groebnerMatrix(27,181); groebnerMatrix(48,179) = groebnerMatrix(48,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(48,124); groebnerMatrix(48,124) = 0.0; groebnerMatrix(48,132) = groebnerMatrix(48,132) - factor * groebnerMatrix(10,177); groebnerMatrix(48,141) = groebnerMatrix(48,141) - factor * groebnerMatrix(10,186); groebnerMatrix(48,195) = groebnerMatrix(48,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,48); groebnerRow47_000000000_f(groebnerMatrix,48); factor = groebnerMatrix(48,127); groebnerMatrix(48,127) = 0.0; groebnerMatrix(48,134) = groebnerMatrix(48,134) - factor * groebnerMatrix(17,179); groebnerMatrix(48,181) = groebnerMatrix(48,181) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(48,130); groebnerMatrix(48,130) = 0.0; groebnerMatrix(48,137) = groebnerMatrix(48,137) - factor * groebnerMatrix(18,182); groebnerMatrix(48,178) = groebnerMatrix(48,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(48,148); groebnerMatrix(48,148) = 0.0; groebnerMatrix(48,153) = groebnerMatrix(48,153) - factor * groebnerMatrix(14,153); groebnerMatrix(48,159) = groebnerMatrix(48,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,48); groebnerRow31_000000000_f(groebnerMatrix,48); groebnerRow32_000000000_f(groebnerMatrix,48); groebnerRow33_000000000_f(groebnerMatrix,48); groebnerRow34_000000000_f(groebnerMatrix,48); groebnerRow35_000000000_f(groebnerMatrix,48); groebnerRow36_000000000_f(groebnerMatrix,48); groebnerRow37_000000000_f(groebnerMatrix,48); groebnerRow38_000000000_f(groebnerMatrix,48); groebnerRow39_000000000_f(groebnerMatrix,48); factor = groebnerMatrix(48,163); groebnerMatrix(48,163) = 0.0; groebnerMatrix(48,171) = groebnerMatrix(48,171) - factor * groebnerMatrix(12,171); groebnerMatrix(48,180) = groebnerMatrix(48,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(48,164); groebnerMatrix(48,164) = 0.0; groebnerMatrix(48,170) = groebnerMatrix(48,170) - factor * groebnerMatrix(20,170); groebnerMatrix(48,192) = groebnerMatrix(48,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(48,165); groebnerMatrix(48,165) = 0.0; groebnerMatrix(48,178) = groebnerMatrix(48,178) - factor * groebnerMatrix(29,178); groebnerMatrix(48,191) = groebnerMatrix(48,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(48,166); groebnerMatrix(48,166) = 0.0; groebnerMatrix(48,174) = groebnerMatrix(48,174) - factor * groebnerMatrix(11,174); groebnerMatrix(48,183) = groebnerMatrix(48,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(48,167); groebnerMatrix(48,167) = 0.0; groebnerMatrix(48,173) = groebnerMatrix(48,173) - factor * groebnerMatrix(21,173); groebnerMatrix(48,189) = groebnerMatrix(48,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(48,168); groebnerMatrix(48,168) = 0.0; groebnerMatrix(48,181) = groebnerMatrix(48,181) - factor * groebnerMatrix(27,181); groebnerMatrix(48,188) = groebnerMatrix(48,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(48,169); groebnerMatrix(48,169) = 0.0; groebnerMatrix(48,177) = groebnerMatrix(48,177) - factor * groebnerMatrix(10,177); groebnerMatrix(48,186) = groebnerMatrix(48,186) - factor * groebnerMatrix(10,186); groebnerMatrix(48,196) = groebnerMatrix(48,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(48,172); groebnerMatrix(48,172) = 0.0; groebnerMatrix(48,179) = groebnerMatrix(48,179) - factor * groebnerMatrix(17,179); groebnerMatrix(48,190) = groebnerMatrix(48,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(48,175); groebnerMatrix(48,175) = 0.0; groebnerMatrix(48,182) = groebnerMatrix(48,182) - factor * groebnerMatrix(18,182); groebnerMatrix(48,187) = groebnerMatrix(48,187) - factor * groebnerMatrix(18,187); sPolynomial49(groebnerMatrix); factor = groebnerMatrix(49,54); groebnerMatrix(49,54) = 0.0; groebnerMatrix(49,80) = groebnerMatrix(49,80) - factor * groebnerMatrix(11,174); groebnerMatrix(49,117) = groebnerMatrix(49,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(49,55); groebnerMatrix(49,55) = 0.0; groebnerMatrix(49,79) = groebnerMatrix(49,79) - factor * groebnerMatrix(21,173); groebnerMatrix(49,159) = groebnerMatrix(49,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(49,56); groebnerMatrix(49,56) = 0.0; groebnerMatrix(49,115) = groebnerMatrix(49,115) - factor * groebnerMatrix(27,181); groebnerMatrix(49,158) = groebnerMatrix(49,158) - factor * groebnerMatrix(27,188); factor = -groebnerMatrix(49,79); groebnerMatrix(49,79) = 0.0; groebnerMatrix(49,110) = groebnerMatrix(49,110) - factor * groebnerMatrix(18,182); groebnerMatrix(49,148) = groebnerMatrix(49,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(49,80); groebnerMatrix(49,80) = 0.0; groebnerMatrix(49,111) = groebnerMatrix(49,111) - factor * groebnerMatrix(18,182); groebnerMatrix(49,152) = groebnerMatrix(49,152) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(49,82); groebnerMatrix(49,82) = 0.0; groebnerMatrix(49,90) = groebnerMatrix(49,90) - factor * groebnerMatrix(12,171); groebnerMatrix(49,127) = groebnerMatrix(49,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(49,83); groebnerMatrix(49,83) = 0.0; groebnerMatrix(49,89) = groebnerMatrix(49,89) - factor * groebnerMatrix(20,170); groebnerMatrix(49,175) = groebnerMatrix(49,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(49,85); groebnerMatrix(49,85) = 0.0; groebnerMatrix(49,93) = groebnerMatrix(49,93) - factor * groebnerMatrix(11,174); groebnerMatrix(49,130) = groebnerMatrix(49,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(49,86); groebnerMatrix(49,86) = 0.0; groebnerMatrix(49,92) = groebnerMatrix(49,92) - factor * groebnerMatrix(21,173); groebnerMatrix(49,172) = groebnerMatrix(49,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(49,88); groebnerMatrix(49,88) = 0.0; groebnerMatrix(49,96) = groebnerMatrix(49,96) - factor * groebnerMatrix(10,177); groebnerMatrix(49,140) = groebnerMatrix(49,140) - factor * groebnerMatrix(10,186); groebnerMatrix(49,194) = groebnerMatrix(49,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,49); groebnerRow41_000000000_f(groebnerMatrix,49); groebnerRow42_000000000_f(groebnerMatrix,49); groebnerRow43_000000000_f(groebnerMatrix,49); groebnerRow44_000000000_f(groebnerMatrix,49); groebnerRow45_000000000_f(groebnerMatrix,49); factor = groebnerMatrix(49,105); groebnerMatrix(49,105) = 0.0; groebnerMatrix(49,112) = groebnerMatrix(49,112) - factor * groebnerMatrix(28,157); groebnerMatrix(49,185) = groebnerMatrix(49,185) - factor * groebnerMatrix(28,194); groebnerRow32_100000000_f(groebnerMatrix,49); groebnerRow33_100000000_f(groebnerMatrix,49); groebnerRow34_100000000_f(groebnerMatrix,49); groebnerRow35_100000000_f(groebnerMatrix,49); groebnerRow36_100000000_f(groebnerMatrix,49); groebnerRow37_100000000_f(groebnerMatrix,49); groebnerRow38_100000000_f(groebnerMatrix,49); groebnerRow39_100000000_f(groebnerMatrix,49); factor = groebnerMatrix(49,118); groebnerMatrix(49,118) = 0.0; groebnerMatrix(49,126) = groebnerMatrix(49,126) - factor * groebnerMatrix(12,171); groebnerMatrix(49,135) = groebnerMatrix(49,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(49,119); groebnerMatrix(49,119) = 0.0; groebnerMatrix(49,125) = groebnerMatrix(49,125) - factor * groebnerMatrix(20,170); groebnerMatrix(49,183) = groebnerMatrix(49,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(49,120); groebnerMatrix(49,120) = 0.0; groebnerMatrix(49,133) = groebnerMatrix(49,133) - factor * groebnerMatrix(29,178); groebnerMatrix(49,182) = groebnerMatrix(49,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(49,121); groebnerMatrix(49,121) = 0.0; groebnerMatrix(49,129) = groebnerMatrix(49,129) - factor * groebnerMatrix(11,174); groebnerMatrix(49,138) = groebnerMatrix(49,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(49,122); groebnerMatrix(49,122) = 0.0; groebnerMatrix(49,128) = groebnerMatrix(49,128) - factor * groebnerMatrix(21,173); groebnerMatrix(49,180) = groebnerMatrix(49,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(49,123); groebnerMatrix(49,123) = 0.0; groebnerMatrix(49,136) = groebnerMatrix(49,136) - factor * groebnerMatrix(27,181); groebnerMatrix(49,179) = groebnerMatrix(49,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(49,124); groebnerMatrix(49,124) = 0.0; groebnerMatrix(49,132) = groebnerMatrix(49,132) - factor * groebnerMatrix(10,177); groebnerMatrix(49,141) = groebnerMatrix(49,141) - factor * groebnerMatrix(10,186); groebnerMatrix(49,195) = groebnerMatrix(49,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,49); groebnerRow47_000000000_f(groebnerMatrix,49); factor = groebnerMatrix(49,127); groebnerMatrix(49,127) = 0.0; groebnerMatrix(49,134) = groebnerMatrix(49,134) - factor * groebnerMatrix(17,179); groebnerMatrix(49,181) = groebnerMatrix(49,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,49); factor = -groebnerMatrix(49,130); groebnerMatrix(49,130) = 0.0; groebnerMatrix(49,137) = groebnerMatrix(49,137) - factor * groebnerMatrix(18,182); groebnerMatrix(49,178) = groebnerMatrix(49,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(49,146); groebnerMatrix(49,146) = 0.0; groebnerMatrix(49,161) = groebnerMatrix(49,161) - factor * groebnerMatrix(23,161); groebnerMatrix(49,185) = groebnerMatrix(49,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(49,148); groebnerMatrix(49,148) = 0.0; groebnerMatrix(49,153) = groebnerMatrix(49,153) - factor * groebnerMatrix(14,153); groebnerMatrix(49,159) = groebnerMatrix(49,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,49); groebnerRow31_000000000_f(groebnerMatrix,49); groebnerRow32_000000000_f(groebnerMatrix,49); groebnerRow33_000000000_f(groebnerMatrix,49); groebnerRow34_000000000_f(groebnerMatrix,49); groebnerRow35_000000000_f(groebnerMatrix,49); groebnerRow36_000000000_f(groebnerMatrix,49); groebnerRow37_000000000_f(groebnerMatrix,49); groebnerRow38_000000000_f(groebnerMatrix,49); groebnerRow39_000000000_f(groebnerMatrix,49); factor = groebnerMatrix(49,163); groebnerMatrix(49,163) = 0.0; groebnerMatrix(49,171) = groebnerMatrix(49,171) - factor * groebnerMatrix(12,171); groebnerMatrix(49,180) = groebnerMatrix(49,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(49,164); groebnerMatrix(49,164) = 0.0; groebnerMatrix(49,170) = groebnerMatrix(49,170) - factor * groebnerMatrix(20,170); groebnerMatrix(49,192) = groebnerMatrix(49,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(49,165); groebnerMatrix(49,165) = 0.0; groebnerMatrix(49,178) = groebnerMatrix(49,178) - factor * groebnerMatrix(29,178); groebnerMatrix(49,191) = groebnerMatrix(49,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(49,166); groebnerMatrix(49,166) = 0.0; groebnerMatrix(49,174) = groebnerMatrix(49,174) - factor * groebnerMatrix(11,174); groebnerMatrix(49,183) = groebnerMatrix(49,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(49,167); groebnerMatrix(49,167) = 0.0; groebnerMatrix(49,173) = groebnerMatrix(49,173) - factor * groebnerMatrix(21,173); groebnerMatrix(49,189) = groebnerMatrix(49,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(49,168); groebnerMatrix(49,168) = 0.0; groebnerMatrix(49,181) = groebnerMatrix(49,181) - factor * groebnerMatrix(27,181); groebnerMatrix(49,188) = groebnerMatrix(49,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(49,169); groebnerMatrix(49,169) = 0.0; groebnerMatrix(49,177) = groebnerMatrix(49,177) - factor * groebnerMatrix(10,177); groebnerMatrix(49,186) = groebnerMatrix(49,186) - factor * groebnerMatrix(10,186); groebnerMatrix(49,196) = groebnerMatrix(49,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(49,172); groebnerMatrix(49,172) = 0.0; groebnerMatrix(49,179) = groebnerMatrix(49,179) - factor * groebnerMatrix(17,179); groebnerMatrix(49,190) = groebnerMatrix(49,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(49,175); groebnerMatrix(49,175) = 0.0; groebnerMatrix(49,182) = groebnerMatrix(49,182) - factor * groebnerMatrix(18,182); groebnerMatrix(49,187) = groebnerMatrix(49,187) - factor * groebnerMatrix(18,187); sPolynomial50(groebnerMatrix); factor = groebnerMatrix(50,53); groebnerMatrix(50,53) = 0.0; groebnerMatrix(50,105) = groebnerMatrix(50,105) - factor * groebnerMatrix(27,181); groebnerMatrix(50,146) = groebnerMatrix(50,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(50,54); groebnerMatrix(50,54) = 0.0; groebnerMatrix(50,80) = groebnerMatrix(50,80) - factor * groebnerMatrix(11,174); groebnerMatrix(50,117) = groebnerMatrix(50,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(50,55); groebnerMatrix(50,55) = 0.0; groebnerMatrix(50,79) = groebnerMatrix(50,79) - factor * groebnerMatrix(21,173); groebnerMatrix(50,159) = groebnerMatrix(50,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(50,56); groebnerMatrix(50,56) = 0.0; groebnerMatrix(50,115) = groebnerMatrix(50,115) - factor * groebnerMatrix(27,181); groebnerMatrix(50,158) = groebnerMatrix(50,158) - factor * groebnerMatrix(27,188); factor = -groebnerMatrix(50,76); groebnerMatrix(50,76) = 0.0; groebnerMatrix(50,107) = groebnerMatrix(50,107) - factor * groebnerMatrix(18,182); groebnerMatrix(50,142) = groebnerMatrix(50,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(50,79); groebnerMatrix(50,79) = 0.0; groebnerMatrix(50,110) = groebnerMatrix(50,110) - factor * groebnerMatrix(18,182); groebnerMatrix(50,148) = groebnerMatrix(50,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(50,80); groebnerMatrix(50,80) = 0.0; groebnerMatrix(50,111) = groebnerMatrix(50,111) - factor * groebnerMatrix(18,182); groebnerMatrix(50,152) = groebnerMatrix(50,152) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(50,82); groebnerMatrix(50,82) = 0.0; groebnerMatrix(50,90) = groebnerMatrix(50,90) - factor * groebnerMatrix(12,171); groebnerMatrix(50,127) = groebnerMatrix(50,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(50,83); groebnerMatrix(50,83) = 0.0; groebnerMatrix(50,89) = groebnerMatrix(50,89) - factor * groebnerMatrix(20,170); groebnerMatrix(50,175) = groebnerMatrix(50,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(50,85); groebnerMatrix(50,85) = 0.0; groebnerMatrix(50,93) = groebnerMatrix(50,93) - factor * groebnerMatrix(11,174); groebnerMatrix(50,130) = groebnerMatrix(50,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(50,86); groebnerMatrix(50,86) = 0.0; groebnerMatrix(50,92) = groebnerMatrix(50,92) - factor * groebnerMatrix(21,173); groebnerMatrix(50,172) = groebnerMatrix(50,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(50,88); groebnerMatrix(50,88) = 0.0; groebnerMatrix(50,96) = groebnerMatrix(50,96) - factor * groebnerMatrix(10,177); groebnerMatrix(50,140) = groebnerMatrix(50,140) - factor * groebnerMatrix(10,186); groebnerMatrix(50,194) = groebnerMatrix(50,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,50); groebnerRow41_000000000_f(groebnerMatrix,50); groebnerRow42_000000000_f(groebnerMatrix,50); groebnerRow43_000000000_f(groebnerMatrix,50); groebnerRow44_000000000_f(groebnerMatrix,50); groebnerRow45_000000000_f(groebnerMatrix,50); factor = groebnerMatrix(50,105); groebnerMatrix(50,105) = 0.0; groebnerMatrix(50,112) = groebnerMatrix(50,112) - factor * groebnerMatrix(28,157); groebnerMatrix(50,185) = groebnerMatrix(50,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,50); groebnerRow31_100000000_f(groebnerMatrix,50); groebnerRow32_100000000_f(groebnerMatrix,50); groebnerRow33_100000000_f(groebnerMatrix,50); groebnerRow34_100000000_f(groebnerMatrix,50); groebnerRow35_100000000_f(groebnerMatrix,50); groebnerRow36_100000000_f(groebnerMatrix,50); groebnerRow37_100000000_f(groebnerMatrix,50); groebnerRow38_100000000_f(groebnerMatrix,50); groebnerRow39_100000000_f(groebnerMatrix,50); factor = groebnerMatrix(50,118); groebnerMatrix(50,118) = 0.0; groebnerMatrix(50,126) = groebnerMatrix(50,126) - factor * groebnerMatrix(12,171); groebnerMatrix(50,135) = groebnerMatrix(50,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(50,119); groebnerMatrix(50,119) = 0.0; groebnerMatrix(50,125) = groebnerMatrix(50,125) - factor * groebnerMatrix(20,170); groebnerMatrix(50,183) = groebnerMatrix(50,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(50,120); groebnerMatrix(50,120) = 0.0; groebnerMatrix(50,133) = groebnerMatrix(50,133) - factor * groebnerMatrix(29,178); groebnerMatrix(50,182) = groebnerMatrix(50,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(50,121); groebnerMatrix(50,121) = 0.0; groebnerMatrix(50,129) = groebnerMatrix(50,129) - factor * groebnerMatrix(11,174); groebnerMatrix(50,138) = groebnerMatrix(50,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(50,122); groebnerMatrix(50,122) = 0.0; groebnerMatrix(50,128) = groebnerMatrix(50,128) - factor * groebnerMatrix(21,173); groebnerMatrix(50,180) = groebnerMatrix(50,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(50,123); groebnerMatrix(50,123) = 0.0; groebnerMatrix(50,136) = groebnerMatrix(50,136) - factor * groebnerMatrix(27,181); groebnerMatrix(50,179) = groebnerMatrix(50,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(50,124); groebnerMatrix(50,124) = 0.0; groebnerMatrix(50,132) = groebnerMatrix(50,132) - factor * groebnerMatrix(10,177); groebnerMatrix(50,141) = groebnerMatrix(50,141) - factor * groebnerMatrix(10,186); groebnerMatrix(50,195) = groebnerMatrix(50,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,50); groebnerRow47_000000000_f(groebnerMatrix,50); factor = groebnerMatrix(50,127); groebnerMatrix(50,127) = 0.0; groebnerMatrix(50,134) = groebnerMatrix(50,134) - factor * groebnerMatrix(17,179); groebnerMatrix(50,181) = groebnerMatrix(50,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,50); groebnerRow49_000000000_f(groebnerMatrix,50); factor = -groebnerMatrix(50,130); groebnerMatrix(50,130) = 0.0; groebnerMatrix(50,137) = groebnerMatrix(50,137) - factor * groebnerMatrix(18,182); groebnerMatrix(50,178) = groebnerMatrix(50,178) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(50,142); groebnerMatrix(50,142) = 0.0; groebnerMatrix(50,144) = groebnerMatrix(50,144) - factor * groebnerMatrix(15,144); groebnerMatrix(50,147) = groebnerMatrix(50,147) - factor * groebnerMatrix(15,147); groebnerMatrix(50,196) = groebnerMatrix(50,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(50,144); groebnerMatrix(50,144) = 0.0; groebnerMatrix(50,156) = groebnerMatrix(50,156) - factor * groebnerMatrix(25,156); groebnerMatrix(50,177) = groebnerMatrix(50,177) - factor * groebnerMatrix(25,177); groebnerMatrix(50,196) = groebnerMatrix(50,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(50,146); groebnerMatrix(50,146) = 0.0; groebnerMatrix(50,161) = groebnerMatrix(50,161) - factor * groebnerMatrix(23,161); groebnerMatrix(50,185) = groebnerMatrix(50,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(50,147); groebnerMatrix(50,147) = 0.0; groebnerMatrix(50,162) = groebnerMatrix(50,162) - factor * groebnerMatrix(22,162); groebnerMatrix(50,186) = groebnerMatrix(50,186) - factor * groebnerMatrix(22,186); groebnerMatrix(50,196) = groebnerMatrix(50,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(50,148); groebnerMatrix(50,148) = 0.0; groebnerMatrix(50,153) = groebnerMatrix(50,153) - factor * groebnerMatrix(14,153); groebnerMatrix(50,159) = groebnerMatrix(50,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,50); groebnerRow31_000000000_f(groebnerMatrix,50); groebnerRow32_000000000_f(groebnerMatrix,50); groebnerRow33_000000000_f(groebnerMatrix,50); groebnerRow34_000000000_f(groebnerMatrix,50); groebnerRow35_000000000_f(groebnerMatrix,50); groebnerRow36_000000000_f(groebnerMatrix,50); groebnerRow37_000000000_f(groebnerMatrix,50); groebnerRow38_000000000_f(groebnerMatrix,50); groebnerRow39_000000000_f(groebnerMatrix,50); factor = groebnerMatrix(50,163); groebnerMatrix(50,163) = 0.0; groebnerMatrix(50,171) = groebnerMatrix(50,171) - factor * groebnerMatrix(12,171); groebnerMatrix(50,180) = groebnerMatrix(50,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(50,164); groebnerMatrix(50,164) = 0.0; groebnerMatrix(50,170) = groebnerMatrix(50,170) - factor * groebnerMatrix(20,170); groebnerMatrix(50,192) = groebnerMatrix(50,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(50,165); groebnerMatrix(50,165) = 0.0; groebnerMatrix(50,178) = groebnerMatrix(50,178) - factor * groebnerMatrix(29,178); groebnerMatrix(50,191) = groebnerMatrix(50,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(50,166); groebnerMatrix(50,166) = 0.0; groebnerMatrix(50,174) = groebnerMatrix(50,174) - factor * groebnerMatrix(11,174); groebnerMatrix(50,183) = groebnerMatrix(50,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(50,167); groebnerMatrix(50,167) = 0.0; groebnerMatrix(50,173) = groebnerMatrix(50,173) - factor * groebnerMatrix(21,173); groebnerMatrix(50,189) = groebnerMatrix(50,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(50,168); groebnerMatrix(50,168) = 0.0; groebnerMatrix(50,181) = groebnerMatrix(50,181) - factor * groebnerMatrix(27,181); groebnerMatrix(50,188) = groebnerMatrix(50,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(50,169); groebnerMatrix(50,169) = 0.0; groebnerMatrix(50,177) = groebnerMatrix(50,177) - factor * groebnerMatrix(10,177); groebnerMatrix(50,186) = groebnerMatrix(50,186) - factor * groebnerMatrix(10,186); groebnerMatrix(50,196) = groebnerMatrix(50,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(50,172); groebnerMatrix(50,172) = 0.0; groebnerMatrix(50,179) = groebnerMatrix(50,179) - factor * groebnerMatrix(17,179); groebnerMatrix(50,190) = groebnerMatrix(50,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(50,175); groebnerMatrix(50,175) = 0.0; groebnerMatrix(50,182) = groebnerMatrix(50,182) - factor * groebnerMatrix(18,182); groebnerMatrix(50,187) = groebnerMatrix(50,187) - factor * groebnerMatrix(18,187); sPolynomial51(groebnerMatrix); factor = groebnerMatrix(51,52); groebnerMatrix(51,52) = 0.0; groebnerMatrix(51,76) = groebnerMatrix(51,76) - factor * groebnerMatrix(20,170); groebnerMatrix(51,162) = groebnerMatrix(51,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(51,53); groebnerMatrix(51,53) = 0.0; groebnerMatrix(51,105) = groebnerMatrix(51,105) - factor * groebnerMatrix(27,181); groebnerMatrix(51,146) = groebnerMatrix(51,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(51,54); groebnerMatrix(51,54) = 0.0; groebnerMatrix(51,80) = groebnerMatrix(51,80) - factor * groebnerMatrix(11,174); groebnerMatrix(51,117) = groebnerMatrix(51,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(51,55); groebnerMatrix(51,55) = 0.0; groebnerMatrix(51,79) = groebnerMatrix(51,79) - factor * groebnerMatrix(21,173); groebnerMatrix(51,159) = groebnerMatrix(51,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(51,56); groebnerMatrix(51,56) = 0.0; groebnerMatrix(51,115) = groebnerMatrix(51,115) - factor * groebnerMatrix(27,181); groebnerMatrix(51,158) = groebnerMatrix(51,158) - factor * groebnerMatrix(27,188); factor = -groebnerMatrix(51,76); groebnerMatrix(51,76) = 0.0; groebnerMatrix(51,107) = groebnerMatrix(51,107) - factor * groebnerMatrix(18,182); groebnerMatrix(51,142) = groebnerMatrix(51,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(51,77); groebnerMatrix(51,77) = 0.0; groebnerMatrix(51,108) = groebnerMatrix(51,108) - factor * groebnerMatrix(18,182); groebnerMatrix(51,143) = groebnerMatrix(51,143) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(51,79); groebnerMatrix(51,79) = 0.0; groebnerMatrix(51,110) = groebnerMatrix(51,110) - factor * groebnerMatrix(18,182); groebnerMatrix(51,148) = groebnerMatrix(51,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(51,80); groebnerMatrix(51,80) = 0.0; groebnerMatrix(51,111) = groebnerMatrix(51,111) - factor * groebnerMatrix(18,182); groebnerMatrix(51,152) = groebnerMatrix(51,152) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(51,82); groebnerMatrix(51,82) = 0.0; groebnerMatrix(51,90) = groebnerMatrix(51,90) - factor * groebnerMatrix(12,171); groebnerMatrix(51,127) = groebnerMatrix(51,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(51,83); groebnerMatrix(51,83) = 0.0; groebnerMatrix(51,89) = groebnerMatrix(51,89) - factor * groebnerMatrix(20,170); groebnerMatrix(51,175) = groebnerMatrix(51,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(51,85); groebnerMatrix(51,85) = 0.0; groebnerMatrix(51,93) = groebnerMatrix(51,93) - factor * groebnerMatrix(11,174); groebnerMatrix(51,130) = groebnerMatrix(51,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(51,86); groebnerMatrix(51,86) = 0.0; groebnerMatrix(51,92) = groebnerMatrix(51,92) - factor * groebnerMatrix(21,173); groebnerMatrix(51,172) = groebnerMatrix(51,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(51,88); groebnerMatrix(51,88) = 0.0; groebnerMatrix(51,96) = groebnerMatrix(51,96) - factor * groebnerMatrix(10,177); groebnerMatrix(51,140) = groebnerMatrix(51,140) - factor * groebnerMatrix(10,186); groebnerMatrix(51,194) = groebnerMatrix(51,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,51); groebnerRow41_000000000_f(groebnerMatrix,51); groebnerRow42_000000000_f(groebnerMatrix,51); groebnerRow43_000000000_f(groebnerMatrix,51); groebnerRow44_000000000_f(groebnerMatrix,51); groebnerRow45_000000000_f(groebnerMatrix,51); factor = groebnerMatrix(51,105); groebnerMatrix(51,105) = 0.0; groebnerMatrix(51,112) = groebnerMatrix(51,112) - factor * groebnerMatrix(28,157); groebnerMatrix(51,185) = groebnerMatrix(51,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,51); groebnerRow31_100000000_f(groebnerMatrix,51); groebnerRow32_100000000_f(groebnerMatrix,51); groebnerRow33_100000000_f(groebnerMatrix,51); groebnerRow34_100000000_f(groebnerMatrix,51); groebnerRow35_100000000_f(groebnerMatrix,51); groebnerRow36_100000000_f(groebnerMatrix,51); groebnerRow37_100000000_f(groebnerMatrix,51); groebnerRow38_100000000_f(groebnerMatrix,51); groebnerRow39_100000000_f(groebnerMatrix,51); factor = groebnerMatrix(51,118); groebnerMatrix(51,118) = 0.0; groebnerMatrix(51,126) = groebnerMatrix(51,126) - factor * groebnerMatrix(12,171); groebnerMatrix(51,135) = groebnerMatrix(51,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(51,119); groebnerMatrix(51,119) = 0.0; groebnerMatrix(51,125) = groebnerMatrix(51,125) - factor * groebnerMatrix(20,170); groebnerMatrix(51,183) = groebnerMatrix(51,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(51,120); groebnerMatrix(51,120) = 0.0; groebnerMatrix(51,133) = groebnerMatrix(51,133) - factor * groebnerMatrix(29,178); groebnerMatrix(51,182) = groebnerMatrix(51,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(51,121); groebnerMatrix(51,121) = 0.0; groebnerMatrix(51,129) = groebnerMatrix(51,129) - factor * groebnerMatrix(11,174); groebnerMatrix(51,138) = groebnerMatrix(51,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(51,122); groebnerMatrix(51,122) = 0.0; groebnerMatrix(51,128) = groebnerMatrix(51,128) - factor * groebnerMatrix(21,173); groebnerMatrix(51,180) = groebnerMatrix(51,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(51,123); groebnerMatrix(51,123) = 0.0; groebnerMatrix(51,136) = groebnerMatrix(51,136) - factor * groebnerMatrix(27,181); groebnerMatrix(51,179) = groebnerMatrix(51,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(51,124); groebnerMatrix(51,124) = 0.0; groebnerMatrix(51,132) = groebnerMatrix(51,132) - factor * groebnerMatrix(10,177); groebnerMatrix(51,141) = groebnerMatrix(51,141) - factor * groebnerMatrix(10,186); groebnerMatrix(51,195) = groebnerMatrix(51,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,51); groebnerRow47_000000000_f(groebnerMatrix,51); factor = groebnerMatrix(51,127); groebnerMatrix(51,127) = 0.0; groebnerMatrix(51,134) = groebnerMatrix(51,134) - factor * groebnerMatrix(17,179); groebnerMatrix(51,181) = groebnerMatrix(51,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,51); groebnerRow49_000000000_f(groebnerMatrix,51); factor = -groebnerMatrix(51,130); groebnerMatrix(51,130) = 0.0; groebnerMatrix(51,137) = groebnerMatrix(51,137) - factor * groebnerMatrix(18,182); groebnerMatrix(51,178) = groebnerMatrix(51,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,51); factor = groebnerMatrix(51,142); groebnerMatrix(51,142) = 0.0; groebnerMatrix(51,144) = groebnerMatrix(51,144) - factor * groebnerMatrix(15,144); groebnerMatrix(51,147) = groebnerMatrix(51,147) - factor * groebnerMatrix(15,147); groebnerMatrix(51,196) = groebnerMatrix(51,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(51,143); groebnerMatrix(51,143) = 0.0; groebnerMatrix(51,155) = groebnerMatrix(51,155) - factor * groebnerMatrix(26,155); groebnerMatrix(51,176) = groebnerMatrix(51,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(51,144); groebnerMatrix(51,144) = 0.0; groebnerMatrix(51,156) = groebnerMatrix(51,156) - factor * groebnerMatrix(25,156); groebnerMatrix(51,177) = groebnerMatrix(51,177) - factor * groebnerMatrix(25,177); groebnerMatrix(51,196) = groebnerMatrix(51,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(51,146); groebnerMatrix(51,146) = 0.0; groebnerMatrix(51,161) = groebnerMatrix(51,161) - factor * groebnerMatrix(23,161); groebnerMatrix(51,185) = groebnerMatrix(51,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(51,147); groebnerMatrix(51,147) = 0.0; groebnerMatrix(51,162) = groebnerMatrix(51,162) - factor * groebnerMatrix(22,162); groebnerMatrix(51,186) = groebnerMatrix(51,186) - factor * groebnerMatrix(22,186); groebnerMatrix(51,196) = groebnerMatrix(51,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(51,148); groebnerMatrix(51,148) = 0.0; groebnerMatrix(51,153) = groebnerMatrix(51,153) - factor * groebnerMatrix(14,153); groebnerMatrix(51,159) = groebnerMatrix(51,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,51); groebnerRow31_000000000_f(groebnerMatrix,51); groebnerRow32_000000000_f(groebnerMatrix,51); groebnerRow33_000000000_f(groebnerMatrix,51); groebnerRow34_000000000_f(groebnerMatrix,51); groebnerRow35_000000000_f(groebnerMatrix,51); groebnerRow36_000000000_f(groebnerMatrix,51); groebnerRow37_000000000_f(groebnerMatrix,51); groebnerRow38_000000000_f(groebnerMatrix,51); groebnerRow39_000000000_f(groebnerMatrix,51); factor = groebnerMatrix(51,163); groebnerMatrix(51,163) = 0.0; groebnerMatrix(51,171) = groebnerMatrix(51,171) - factor * groebnerMatrix(12,171); groebnerMatrix(51,180) = groebnerMatrix(51,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(51,164); groebnerMatrix(51,164) = 0.0; groebnerMatrix(51,170) = groebnerMatrix(51,170) - factor * groebnerMatrix(20,170); groebnerMatrix(51,192) = groebnerMatrix(51,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(51,165); groebnerMatrix(51,165) = 0.0; groebnerMatrix(51,178) = groebnerMatrix(51,178) - factor * groebnerMatrix(29,178); groebnerMatrix(51,191) = groebnerMatrix(51,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(51,166); groebnerMatrix(51,166) = 0.0; groebnerMatrix(51,174) = groebnerMatrix(51,174) - factor * groebnerMatrix(11,174); groebnerMatrix(51,183) = groebnerMatrix(51,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(51,167); groebnerMatrix(51,167) = 0.0; groebnerMatrix(51,173) = groebnerMatrix(51,173) - factor * groebnerMatrix(21,173); groebnerMatrix(51,189) = groebnerMatrix(51,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(51,168); groebnerMatrix(51,168) = 0.0; groebnerMatrix(51,181) = groebnerMatrix(51,181) - factor * groebnerMatrix(27,181); groebnerMatrix(51,188) = groebnerMatrix(51,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(51,169); groebnerMatrix(51,169) = 0.0; groebnerMatrix(51,177) = groebnerMatrix(51,177) - factor * groebnerMatrix(10,177); groebnerMatrix(51,186) = groebnerMatrix(51,186) - factor * groebnerMatrix(10,186); groebnerMatrix(51,196) = groebnerMatrix(51,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(51,172); groebnerMatrix(51,172) = 0.0; groebnerMatrix(51,179) = groebnerMatrix(51,179) - factor * groebnerMatrix(17,179); groebnerMatrix(51,190) = groebnerMatrix(51,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(51,175); groebnerMatrix(51,175) = 0.0; groebnerMatrix(51,182) = groebnerMatrix(51,182) - factor * groebnerMatrix(18,182); groebnerMatrix(51,187) = groebnerMatrix(51,187) - factor * groebnerMatrix(18,187); sPolynomial52(groebnerMatrix); factor = groebnerMatrix(52,51); groebnerMatrix(52,51) = 0.0; groebnerMatrix(52,77) = groebnerMatrix(52,77) - factor * groebnerMatrix(12,171); groebnerMatrix(52,114) = groebnerMatrix(52,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(52,52); groebnerMatrix(52,52) = 0.0; groebnerMatrix(52,76) = groebnerMatrix(52,76) - factor * groebnerMatrix(20,170); groebnerMatrix(52,162) = groebnerMatrix(52,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(52,53); groebnerMatrix(52,53) = 0.0; groebnerMatrix(52,105) = groebnerMatrix(52,105) - factor * groebnerMatrix(27,181); groebnerMatrix(52,146) = groebnerMatrix(52,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(52,54); groebnerMatrix(52,54) = 0.0; groebnerMatrix(52,80) = groebnerMatrix(52,80) - factor * groebnerMatrix(11,174); groebnerMatrix(52,117) = groebnerMatrix(52,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(52,55); groebnerMatrix(52,55) = 0.0; groebnerMatrix(52,79) = groebnerMatrix(52,79) - factor * groebnerMatrix(21,173); groebnerMatrix(52,159) = groebnerMatrix(52,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(52,56); groebnerMatrix(52,56) = 0.0; groebnerMatrix(52,115) = groebnerMatrix(52,115) - factor * groebnerMatrix(27,181); groebnerMatrix(52,158) = groebnerMatrix(52,158) - factor * groebnerMatrix(27,188); groebnerRow32_010000000_f(groebnerMatrix,52); groebnerRow33_010000000_f(groebnerMatrix,52); factor = -groebnerMatrix(52,76); groebnerMatrix(52,76) = 0.0; groebnerMatrix(52,107) = groebnerMatrix(52,107) - factor * groebnerMatrix(18,182); groebnerMatrix(52,142) = groebnerMatrix(52,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(52,77); groebnerMatrix(52,77) = 0.0; groebnerMatrix(52,108) = groebnerMatrix(52,108) - factor * groebnerMatrix(18,182); groebnerMatrix(52,143) = groebnerMatrix(52,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(52,78); groebnerMatrix(52,78) = 0.0; groebnerMatrix(52,113) = groebnerMatrix(52,113) - factor * groebnerMatrix(17,179); groebnerMatrix(52,160) = groebnerMatrix(52,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(52,79); groebnerMatrix(52,79) = 0.0; groebnerMatrix(52,110) = groebnerMatrix(52,110) - factor * groebnerMatrix(18,182); groebnerMatrix(52,148) = groebnerMatrix(52,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(52,80); groebnerMatrix(52,80) = 0.0; groebnerMatrix(52,111) = groebnerMatrix(52,111) - factor * groebnerMatrix(18,182); groebnerMatrix(52,152) = groebnerMatrix(52,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(52,81); groebnerMatrix(52,81) = 0.0; groebnerMatrix(52,116) = groebnerMatrix(52,116) - factor * groebnerMatrix(18,182); groebnerMatrix(52,157) = groebnerMatrix(52,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(52,82); groebnerMatrix(52,82) = 0.0; groebnerMatrix(52,90) = groebnerMatrix(52,90) - factor * groebnerMatrix(12,171); groebnerMatrix(52,127) = groebnerMatrix(52,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(52,83); groebnerMatrix(52,83) = 0.0; groebnerMatrix(52,89) = groebnerMatrix(52,89) - factor * groebnerMatrix(20,170); groebnerMatrix(52,175) = groebnerMatrix(52,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(52,85); groebnerMatrix(52,85) = 0.0; groebnerMatrix(52,93) = groebnerMatrix(52,93) - factor * groebnerMatrix(11,174); groebnerMatrix(52,130) = groebnerMatrix(52,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(52,86); groebnerMatrix(52,86) = 0.0; groebnerMatrix(52,92) = groebnerMatrix(52,92) - factor * groebnerMatrix(21,173); groebnerMatrix(52,172) = groebnerMatrix(52,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(52,88); groebnerMatrix(52,88) = 0.0; groebnerMatrix(52,96) = groebnerMatrix(52,96) - factor * groebnerMatrix(10,177); groebnerMatrix(52,140) = groebnerMatrix(52,140) - factor * groebnerMatrix(10,186); groebnerMatrix(52,194) = groebnerMatrix(52,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,52); groebnerRow41_000000000_f(groebnerMatrix,52); groebnerRow42_000000000_f(groebnerMatrix,52); groebnerRow43_000000000_f(groebnerMatrix,52); groebnerRow44_000000000_f(groebnerMatrix,52); groebnerRow45_000000000_f(groebnerMatrix,52); factor = groebnerMatrix(52,105); groebnerMatrix(52,105) = 0.0; groebnerMatrix(52,112) = groebnerMatrix(52,112) - factor * groebnerMatrix(28,157); groebnerMatrix(52,185) = groebnerMatrix(52,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,52); groebnerRow31_100000000_f(groebnerMatrix,52); groebnerRow32_100000000_f(groebnerMatrix,52); groebnerRow33_100000000_f(groebnerMatrix,52); groebnerRow34_100000000_f(groebnerMatrix,52); groebnerRow35_100000000_f(groebnerMatrix,52); groebnerRow36_100000000_f(groebnerMatrix,52); groebnerRow37_100000000_f(groebnerMatrix,52); groebnerRow38_100000000_f(groebnerMatrix,52); groebnerRow39_100000000_f(groebnerMatrix,52); factor = groebnerMatrix(52,118); groebnerMatrix(52,118) = 0.0; groebnerMatrix(52,126) = groebnerMatrix(52,126) - factor * groebnerMatrix(12,171); groebnerMatrix(52,135) = groebnerMatrix(52,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(52,119); groebnerMatrix(52,119) = 0.0; groebnerMatrix(52,125) = groebnerMatrix(52,125) - factor * groebnerMatrix(20,170); groebnerMatrix(52,183) = groebnerMatrix(52,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(52,120); groebnerMatrix(52,120) = 0.0; groebnerMatrix(52,133) = groebnerMatrix(52,133) - factor * groebnerMatrix(29,178); groebnerMatrix(52,182) = groebnerMatrix(52,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(52,121); groebnerMatrix(52,121) = 0.0; groebnerMatrix(52,129) = groebnerMatrix(52,129) - factor * groebnerMatrix(11,174); groebnerMatrix(52,138) = groebnerMatrix(52,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(52,122); groebnerMatrix(52,122) = 0.0; groebnerMatrix(52,128) = groebnerMatrix(52,128) - factor * groebnerMatrix(21,173); groebnerMatrix(52,180) = groebnerMatrix(52,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(52,123); groebnerMatrix(52,123) = 0.0; groebnerMatrix(52,136) = groebnerMatrix(52,136) - factor * groebnerMatrix(27,181); groebnerMatrix(52,179) = groebnerMatrix(52,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(52,124); groebnerMatrix(52,124) = 0.0; groebnerMatrix(52,132) = groebnerMatrix(52,132) - factor * groebnerMatrix(10,177); groebnerMatrix(52,141) = groebnerMatrix(52,141) - factor * groebnerMatrix(10,186); groebnerMatrix(52,195) = groebnerMatrix(52,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,52); groebnerRow47_000000000_f(groebnerMatrix,52); factor = groebnerMatrix(52,127); groebnerMatrix(52,127) = 0.0; groebnerMatrix(52,134) = groebnerMatrix(52,134) - factor * groebnerMatrix(17,179); groebnerMatrix(52,181) = groebnerMatrix(52,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,52); groebnerRow49_000000000_f(groebnerMatrix,52); factor = -groebnerMatrix(52,130); groebnerMatrix(52,130) = 0.0; groebnerMatrix(52,137) = groebnerMatrix(52,137) - factor * groebnerMatrix(18,182); groebnerMatrix(52,178) = groebnerMatrix(52,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,52); groebnerRow51_000000000_f(groebnerMatrix,52); factor = groebnerMatrix(52,142); groebnerMatrix(52,142) = 0.0; groebnerMatrix(52,144) = groebnerMatrix(52,144) - factor * groebnerMatrix(15,144); groebnerMatrix(52,147) = groebnerMatrix(52,147) - factor * groebnerMatrix(15,147); groebnerMatrix(52,196) = groebnerMatrix(52,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(52,143); groebnerMatrix(52,143) = 0.0; groebnerMatrix(52,155) = groebnerMatrix(52,155) - factor * groebnerMatrix(26,155); groebnerMatrix(52,176) = groebnerMatrix(52,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(52,144); groebnerMatrix(52,144) = 0.0; groebnerMatrix(52,156) = groebnerMatrix(52,156) - factor * groebnerMatrix(25,156); groebnerMatrix(52,177) = groebnerMatrix(52,177) - factor * groebnerMatrix(25,177); groebnerMatrix(52,196) = groebnerMatrix(52,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(52,146); groebnerMatrix(52,146) = 0.0; groebnerMatrix(52,161) = groebnerMatrix(52,161) - factor * groebnerMatrix(23,161); groebnerMatrix(52,185) = groebnerMatrix(52,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(52,147); groebnerMatrix(52,147) = 0.0; groebnerMatrix(52,162) = groebnerMatrix(52,162) - factor * groebnerMatrix(22,162); groebnerMatrix(52,186) = groebnerMatrix(52,186) - factor * groebnerMatrix(22,186); groebnerMatrix(52,196) = groebnerMatrix(52,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(52,148); groebnerMatrix(52,148) = 0.0; groebnerMatrix(52,153) = groebnerMatrix(52,153) - factor * groebnerMatrix(14,153); groebnerMatrix(52,159) = groebnerMatrix(52,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,52); groebnerRow31_000000000_f(groebnerMatrix,52); factor = -groebnerMatrix(52,154); groebnerMatrix(52,154) = 0.0; groebnerMatrix(52,158) = groebnerMatrix(52,158) - factor * groebnerMatrix(16,158); groebnerMatrix(52,193) = groebnerMatrix(52,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,52); groebnerRow33_000000000_f(groebnerMatrix,52); groebnerRow34_000000000_f(groebnerMatrix,52); groebnerRow35_000000000_f(groebnerMatrix,52); groebnerRow36_000000000_f(groebnerMatrix,52); groebnerRow37_000000000_f(groebnerMatrix,52); groebnerRow38_000000000_f(groebnerMatrix,52); groebnerRow39_000000000_f(groebnerMatrix,52); factor = groebnerMatrix(52,163); groebnerMatrix(52,163) = 0.0; groebnerMatrix(52,171) = groebnerMatrix(52,171) - factor * groebnerMatrix(12,171); groebnerMatrix(52,180) = groebnerMatrix(52,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(52,164); groebnerMatrix(52,164) = 0.0; groebnerMatrix(52,170) = groebnerMatrix(52,170) - factor * groebnerMatrix(20,170); groebnerMatrix(52,192) = groebnerMatrix(52,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(52,165); groebnerMatrix(52,165) = 0.0; groebnerMatrix(52,178) = groebnerMatrix(52,178) - factor * groebnerMatrix(29,178); groebnerMatrix(52,191) = groebnerMatrix(52,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(52,166); groebnerMatrix(52,166) = 0.0; groebnerMatrix(52,174) = groebnerMatrix(52,174) - factor * groebnerMatrix(11,174); groebnerMatrix(52,183) = groebnerMatrix(52,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(52,167); groebnerMatrix(52,167) = 0.0; groebnerMatrix(52,173) = groebnerMatrix(52,173) - factor * groebnerMatrix(21,173); groebnerMatrix(52,189) = groebnerMatrix(52,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(52,168); groebnerMatrix(52,168) = 0.0; groebnerMatrix(52,181) = groebnerMatrix(52,181) - factor * groebnerMatrix(27,181); groebnerMatrix(52,188) = groebnerMatrix(52,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(52,169); groebnerMatrix(52,169) = 0.0; groebnerMatrix(52,177) = groebnerMatrix(52,177) - factor * groebnerMatrix(10,177); groebnerMatrix(52,186) = groebnerMatrix(52,186) - factor * groebnerMatrix(10,186); groebnerMatrix(52,196) = groebnerMatrix(52,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(52,172); groebnerMatrix(52,172) = 0.0; groebnerMatrix(52,179) = groebnerMatrix(52,179) - factor * groebnerMatrix(17,179); groebnerMatrix(52,190) = groebnerMatrix(52,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(52,175); groebnerMatrix(52,175) = 0.0; groebnerMatrix(52,182) = groebnerMatrix(52,182) - factor * groebnerMatrix(18,182); groebnerMatrix(52,187) = groebnerMatrix(52,187) - factor * groebnerMatrix(18,187); sPolynomial53(groebnerMatrix); factor = -groebnerMatrix(53,50); groebnerMatrix(53,50) = 0.0; groebnerMatrix(53,74) = groebnerMatrix(53,74) - factor * groebnerMatrix(21,173); groebnerMatrix(53,154) = groebnerMatrix(53,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(53,51); groebnerMatrix(53,51) = 0.0; groebnerMatrix(53,77) = groebnerMatrix(53,77) - factor * groebnerMatrix(12,171); groebnerMatrix(53,114) = groebnerMatrix(53,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(53,52); groebnerMatrix(53,52) = 0.0; groebnerMatrix(53,76) = groebnerMatrix(53,76) - factor * groebnerMatrix(20,170); groebnerMatrix(53,162) = groebnerMatrix(53,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(53,53); groebnerMatrix(53,53) = 0.0; groebnerMatrix(53,105) = groebnerMatrix(53,105) - factor * groebnerMatrix(27,181); groebnerMatrix(53,146) = groebnerMatrix(53,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(53,54); groebnerMatrix(53,54) = 0.0; groebnerMatrix(53,80) = groebnerMatrix(53,80) - factor * groebnerMatrix(11,174); groebnerMatrix(53,117) = groebnerMatrix(53,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(53,55); groebnerMatrix(53,55) = 0.0; groebnerMatrix(53,79) = groebnerMatrix(53,79) - factor * groebnerMatrix(21,173); groebnerMatrix(53,159) = groebnerMatrix(53,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(53,56); groebnerMatrix(53,56) = 0.0; groebnerMatrix(53,115) = groebnerMatrix(53,115) - factor * groebnerMatrix(27,181); groebnerMatrix(53,158) = groebnerMatrix(53,158) - factor * groebnerMatrix(27,188); groebnerRow32_010000000_f(groebnerMatrix,53); groebnerRow33_010000000_f(groebnerMatrix,53); factor = -groebnerMatrix(53,76); groebnerMatrix(53,76) = 0.0; groebnerMatrix(53,107) = groebnerMatrix(53,107) - factor * groebnerMatrix(18,182); groebnerMatrix(53,142) = groebnerMatrix(53,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(53,77); groebnerMatrix(53,77) = 0.0; groebnerMatrix(53,108) = groebnerMatrix(53,108) - factor * groebnerMatrix(18,182); groebnerMatrix(53,143) = groebnerMatrix(53,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(53,78); groebnerMatrix(53,78) = 0.0; groebnerMatrix(53,113) = groebnerMatrix(53,113) - factor * groebnerMatrix(17,179); groebnerMatrix(53,160) = groebnerMatrix(53,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(53,79); groebnerMatrix(53,79) = 0.0; groebnerMatrix(53,110) = groebnerMatrix(53,110) - factor * groebnerMatrix(18,182); groebnerMatrix(53,148) = groebnerMatrix(53,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(53,80); groebnerMatrix(53,80) = 0.0; groebnerMatrix(53,111) = groebnerMatrix(53,111) - factor * groebnerMatrix(18,182); groebnerMatrix(53,152) = groebnerMatrix(53,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(53,81); groebnerMatrix(53,81) = 0.0; groebnerMatrix(53,116) = groebnerMatrix(53,116) - factor * groebnerMatrix(18,182); groebnerMatrix(53,157) = groebnerMatrix(53,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(53,82); groebnerMatrix(53,82) = 0.0; groebnerMatrix(53,90) = groebnerMatrix(53,90) - factor * groebnerMatrix(12,171); groebnerMatrix(53,127) = groebnerMatrix(53,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(53,83); groebnerMatrix(53,83) = 0.0; groebnerMatrix(53,89) = groebnerMatrix(53,89) - factor * groebnerMatrix(20,170); groebnerMatrix(53,175) = groebnerMatrix(53,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(53,85); groebnerMatrix(53,85) = 0.0; groebnerMatrix(53,93) = groebnerMatrix(53,93) - factor * groebnerMatrix(11,174); groebnerMatrix(53,130) = groebnerMatrix(53,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(53,86); groebnerMatrix(53,86) = 0.0; groebnerMatrix(53,92) = groebnerMatrix(53,92) - factor * groebnerMatrix(21,173); groebnerMatrix(53,172) = groebnerMatrix(53,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(53,88); groebnerMatrix(53,88) = 0.0; groebnerMatrix(53,96) = groebnerMatrix(53,96) - factor * groebnerMatrix(10,177); groebnerMatrix(53,140) = groebnerMatrix(53,140) - factor * groebnerMatrix(10,186); groebnerMatrix(53,194) = groebnerMatrix(53,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,53); groebnerRow41_000000000_f(groebnerMatrix,53); groebnerRow42_000000000_f(groebnerMatrix,53); groebnerRow43_000000000_f(groebnerMatrix,53); groebnerRow44_000000000_f(groebnerMatrix,53); groebnerRow45_000000000_f(groebnerMatrix,53); factor = groebnerMatrix(53,105); groebnerMatrix(53,105) = 0.0; groebnerMatrix(53,112) = groebnerMatrix(53,112) - factor * groebnerMatrix(28,157); groebnerMatrix(53,185) = groebnerMatrix(53,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,53); groebnerRow31_100000000_f(groebnerMatrix,53); groebnerRow32_100000000_f(groebnerMatrix,53); groebnerRow33_100000000_f(groebnerMatrix,53); groebnerRow34_100000000_f(groebnerMatrix,53); groebnerRow35_100000000_f(groebnerMatrix,53); groebnerRow36_100000000_f(groebnerMatrix,53); groebnerRow37_100000000_f(groebnerMatrix,53); groebnerRow38_100000000_f(groebnerMatrix,53); groebnerRow39_100000000_f(groebnerMatrix,53); factor = groebnerMatrix(53,118); groebnerMatrix(53,118) = 0.0; groebnerMatrix(53,126) = groebnerMatrix(53,126) - factor * groebnerMatrix(12,171); groebnerMatrix(53,135) = groebnerMatrix(53,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(53,119); groebnerMatrix(53,119) = 0.0; groebnerMatrix(53,125) = groebnerMatrix(53,125) - factor * groebnerMatrix(20,170); groebnerMatrix(53,183) = groebnerMatrix(53,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(53,120); groebnerMatrix(53,120) = 0.0; groebnerMatrix(53,133) = groebnerMatrix(53,133) - factor * groebnerMatrix(29,178); groebnerMatrix(53,182) = groebnerMatrix(53,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(53,121); groebnerMatrix(53,121) = 0.0; groebnerMatrix(53,129) = groebnerMatrix(53,129) - factor * groebnerMatrix(11,174); groebnerMatrix(53,138) = groebnerMatrix(53,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(53,122); groebnerMatrix(53,122) = 0.0; groebnerMatrix(53,128) = groebnerMatrix(53,128) - factor * groebnerMatrix(21,173); groebnerMatrix(53,180) = groebnerMatrix(53,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(53,123); groebnerMatrix(53,123) = 0.0; groebnerMatrix(53,136) = groebnerMatrix(53,136) - factor * groebnerMatrix(27,181); groebnerMatrix(53,179) = groebnerMatrix(53,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(53,124); groebnerMatrix(53,124) = 0.0; groebnerMatrix(53,132) = groebnerMatrix(53,132) - factor * groebnerMatrix(10,177); groebnerMatrix(53,141) = groebnerMatrix(53,141) - factor * groebnerMatrix(10,186); groebnerMatrix(53,195) = groebnerMatrix(53,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,53); groebnerRow47_000000000_f(groebnerMatrix,53); factor = groebnerMatrix(53,127); groebnerMatrix(53,127) = 0.0; groebnerMatrix(53,134) = groebnerMatrix(53,134) - factor * groebnerMatrix(17,179); groebnerMatrix(53,181) = groebnerMatrix(53,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,53); groebnerRow49_000000000_f(groebnerMatrix,53); factor = -groebnerMatrix(53,130); groebnerMatrix(53,130) = 0.0; groebnerMatrix(53,137) = groebnerMatrix(53,137) - factor * groebnerMatrix(18,182); groebnerMatrix(53,178) = groebnerMatrix(53,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,53); groebnerRow51_000000000_f(groebnerMatrix,53); groebnerRow52_000000000_f(groebnerMatrix,53); factor = groebnerMatrix(53,142); groebnerMatrix(53,142) = 0.0; groebnerMatrix(53,144) = groebnerMatrix(53,144) - factor * groebnerMatrix(15,144); groebnerMatrix(53,147) = groebnerMatrix(53,147) - factor * groebnerMatrix(15,147); groebnerMatrix(53,196) = groebnerMatrix(53,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(53,143); groebnerMatrix(53,143) = 0.0; groebnerMatrix(53,155) = groebnerMatrix(53,155) - factor * groebnerMatrix(26,155); groebnerMatrix(53,176) = groebnerMatrix(53,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(53,144); groebnerMatrix(53,144) = 0.0; groebnerMatrix(53,156) = groebnerMatrix(53,156) - factor * groebnerMatrix(25,156); groebnerMatrix(53,177) = groebnerMatrix(53,177) - factor * groebnerMatrix(25,177); groebnerMatrix(53,196) = groebnerMatrix(53,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(53,146); groebnerMatrix(53,146) = 0.0; groebnerMatrix(53,161) = groebnerMatrix(53,161) - factor * groebnerMatrix(23,161); groebnerMatrix(53,185) = groebnerMatrix(53,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(53,147); groebnerMatrix(53,147) = 0.0; groebnerMatrix(53,162) = groebnerMatrix(53,162) - factor * groebnerMatrix(22,162); groebnerMatrix(53,186) = groebnerMatrix(53,186) - factor * groebnerMatrix(22,186); groebnerMatrix(53,196) = groebnerMatrix(53,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(53,148); groebnerMatrix(53,148) = 0.0; groebnerMatrix(53,153) = groebnerMatrix(53,153) - factor * groebnerMatrix(14,153); groebnerMatrix(53,159) = groebnerMatrix(53,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,53); groebnerRow31_000000000_f(groebnerMatrix,53); factor = -groebnerMatrix(53,154); groebnerMatrix(53,154) = 0.0; groebnerMatrix(53,158) = groebnerMatrix(53,158) - factor * groebnerMatrix(16,158); groebnerMatrix(53,193) = groebnerMatrix(53,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,53); groebnerRow33_000000000_f(groebnerMatrix,53); groebnerRow34_000000000_f(groebnerMatrix,53); groebnerRow35_000000000_f(groebnerMatrix,53); groebnerRow36_000000000_f(groebnerMatrix,53); groebnerRow37_000000000_f(groebnerMatrix,53); groebnerRow38_000000000_f(groebnerMatrix,53); groebnerRow39_000000000_f(groebnerMatrix,53); factor = groebnerMatrix(53,163); groebnerMatrix(53,163) = 0.0; groebnerMatrix(53,171) = groebnerMatrix(53,171) - factor * groebnerMatrix(12,171); groebnerMatrix(53,180) = groebnerMatrix(53,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(53,164); groebnerMatrix(53,164) = 0.0; groebnerMatrix(53,170) = groebnerMatrix(53,170) - factor * groebnerMatrix(20,170); groebnerMatrix(53,192) = groebnerMatrix(53,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(53,165); groebnerMatrix(53,165) = 0.0; groebnerMatrix(53,178) = groebnerMatrix(53,178) - factor * groebnerMatrix(29,178); groebnerMatrix(53,191) = groebnerMatrix(53,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(53,166); groebnerMatrix(53,166) = 0.0; groebnerMatrix(53,174) = groebnerMatrix(53,174) - factor * groebnerMatrix(11,174); groebnerMatrix(53,183) = groebnerMatrix(53,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(53,167); groebnerMatrix(53,167) = 0.0; groebnerMatrix(53,173) = groebnerMatrix(53,173) - factor * groebnerMatrix(21,173); groebnerMatrix(53,189) = groebnerMatrix(53,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(53,168); groebnerMatrix(53,168) = 0.0; groebnerMatrix(53,181) = groebnerMatrix(53,181) - factor * groebnerMatrix(27,181); groebnerMatrix(53,188) = groebnerMatrix(53,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(53,169); groebnerMatrix(53,169) = 0.0; groebnerMatrix(53,177) = groebnerMatrix(53,177) - factor * groebnerMatrix(10,177); groebnerMatrix(53,186) = groebnerMatrix(53,186) - factor * groebnerMatrix(10,186); groebnerMatrix(53,196) = groebnerMatrix(53,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(53,172); groebnerMatrix(53,172) = 0.0; groebnerMatrix(53,179) = groebnerMatrix(53,179) - factor * groebnerMatrix(17,179); groebnerMatrix(53,190) = groebnerMatrix(53,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(53,175); groebnerMatrix(53,175) = 0.0; groebnerMatrix(53,182) = groebnerMatrix(53,182) - factor * groebnerMatrix(18,182); groebnerMatrix(53,187) = groebnerMatrix(53,187) - factor * groebnerMatrix(18,187); sPolynomial54(groebnerMatrix); factor = groebnerMatrix(54,49); groebnerMatrix(54,49) = 0.0; groebnerMatrix(54,75) = groebnerMatrix(54,75) - factor * groebnerMatrix(11,174); groebnerMatrix(54,116) = groebnerMatrix(54,116) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(54,50); groebnerMatrix(54,50) = 0.0; groebnerMatrix(54,74) = groebnerMatrix(54,74) - factor * groebnerMatrix(21,173); groebnerMatrix(54,154) = groebnerMatrix(54,154) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(54,51); groebnerMatrix(54,51) = 0.0; groebnerMatrix(54,77) = groebnerMatrix(54,77) - factor * groebnerMatrix(12,171); groebnerMatrix(54,114) = groebnerMatrix(54,114) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(54,52); groebnerMatrix(54,52) = 0.0; groebnerMatrix(54,76) = groebnerMatrix(54,76) - factor * groebnerMatrix(20,170); groebnerMatrix(54,162) = groebnerMatrix(54,162) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(54,53); groebnerMatrix(54,53) = 0.0; groebnerMatrix(54,105) = groebnerMatrix(54,105) - factor * groebnerMatrix(27,181); groebnerMatrix(54,146) = groebnerMatrix(54,146) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(54,54); groebnerMatrix(54,54) = 0.0; groebnerMatrix(54,80) = groebnerMatrix(54,80) - factor * groebnerMatrix(11,174); groebnerMatrix(54,117) = groebnerMatrix(54,117) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(54,55); groebnerMatrix(54,55) = 0.0; groebnerMatrix(54,79) = groebnerMatrix(54,79) - factor * groebnerMatrix(21,173); groebnerMatrix(54,159) = groebnerMatrix(54,159) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(54,56); groebnerMatrix(54,56) = 0.0; groebnerMatrix(54,115) = groebnerMatrix(54,115) - factor * groebnerMatrix(27,181); groebnerMatrix(54,158) = groebnerMatrix(54,158) - factor * groebnerMatrix(27,188); groebnerRow30_010000000_f(groebnerMatrix,54); groebnerRow31_010000000_f(groebnerMatrix,54); groebnerRow32_010000000_f(groebnerMatrix,54); groebnerRow33_010000000_f(groebnerMatrix,54); factor = -groebnerMatrix(54,76); groebnerMatrix(54,76) = 0.0; groebnerMatrix(54,107) = groebnerMatrix(54,107) - factor * groebnerMatrix(18,182); groebnerMatrix(54,142) = groebnerMatrix(54,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(54,77); groebnerMatrix(54,77) = 0.0; groebnerMatrix(54,108) = groebnerMatrix(54,108) - factor * groebnerMatrix(18,182); groebnerMatrix(54,143) = groebnerMatrix(54,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(54,78); groebnerMatrix(54,78) = 0.0; groebnerMatrix(54,113) = groebnerMatrix(54,113) - factor * groebnerMatrix(17,179); groebnerMatrix(54,160) = groebnerMatrix(54,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(54,79); groebnerMatrix(54,79) = 0.0; groebnerMatrix(54,110) = groebnerMatrix(54,110) - factor * groebnerMatrix(18,182); groebnerMatrix(54,148) = groebnerMatrix(54,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(54,80); groebnerMatrix(54,80) = 0.0; groebnerMatrix(54,111) = groebnerMatrix(54,111) - factor * groebnerMatrix(18,182); groebnerMatrix(54,152) = groebnerMatrix(54,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(54,81); groebnerMatrix(54,81) = 0.0; groebnerMatrix(54,116) = groebnerMatrix(54,116) - factor * groebnerMatrix(18,182); groebnerMatrix(54,157) = groebnerMatrix(54,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(54,82); groebnerMatrix(54,82) = 0.0; groebnerMatrix(54,90) = groebnerMatrix(54,90) - factor * groebnerMatrix(12,171); groebnerMatrix(54,127) = groebnerMatrix(54,127) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(54,83); groebnerMatrix(54,83) = 0.0; groebnerMatrix(54,89) = groebnerMatrix(54,89) - factor * groebnerMatrix(20,170); groebnerMatrix(54,175) = groebnerMatrix(54,175) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(54,85); groebnerMatrix(54,85) = 0.0; groebnerMatrix(54,93) = groebnerMatrix(54,93) - factor * groebnerMatrix(11,174); groebnerMatrix(54,130) = groebnerMatrix(54,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(54,86); groebnerMatrix(54,86) = 0.0; groebnerMatrix(54,92) = groebnerMatrix(54,92) - factor * groebnerMatrix(21,173); groebnerMatrix(54,172) = groebnerMatrix(54,172) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(54,88); groebnerMatrix(54,88) = 0.0; groebnerMatrix(54,96) = groebnerMatrix(54,96) - factor * groebnerMatrix(10,177); groebnerMatrix(54,140) = groebnerMatrix(54,140) - factor * groebnerMatrix(10,186); groebnerMatrix(54,194) = groebnerMatrix(54,194) - factor * groebnerMatrix(10,196); groebnerRow40_000000000_f(groebnerMatrix,54); groebnerRow41_000000000_f(groebnerMatrix,54); groebnerRow42_000000000_f(groebnerMatrix,54); groebnerRow43_000000000_f(groebnerMatrix,54); groebnerRow44_000000000_f(groebnerMatrix,54); groebnerRow45_000000000_f(groebnerMatrix,54); factor = groebnerMatrix(54,105); groebnerMatrix(54,105) = 0.0; groebnerMatrix(54,112) = groebnerMatrix(54,112) - factor * groebnerMatrix(28,157); groebnerMatrix(54,185) = groebnerMatrix(54,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,54); groebnerRow31_100000000_f(groebnerMatrix,54); groebnerRow32_100000000_f(groebnerMatrix,54); groebnerRow33_100000000_f(groebnerMatrix,54); groebnerRow34_100000000_f(groebnerMatrix,54); groebnerRow35_100000000_f(groebnerMatrix,54); groebnerRow36_100000000_f(groebnerMatrix,54); groebnerRow37_100000000_f(groebnerMatrix,54); groebnerRow38_100000000_f(groebnerMatrix,54); groebnerRow39_100000000_f(groebnerMatrix,54); factor = groebnerMatrix(54,118); groebnerMatrix(54,118) = 0.0; groebnerMatrix(54,126) = groebnerMatrix(54,126) - factor * groebnerMatrix(12,171); groebnerMatrix(54,135) = groebnerMatrix(54,135) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(54,119); groebnerMatrix(54,119) = 0.0; groebnerMatrix(54,125) = groebnerMatrix(54,125) - factor * groebnerMatrix(20,170); groebnerMatrix(54,183) = groebnerMatrix(54,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(54,120); groebnerMatrix(54,120) = 0.0; groebnerMatrix(54,133) = groebnerMatrix(54,133) - factor * groebnerMatrix(29,178); groebnerMatrix(54,182) = groebnerMatrix(54,182) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(54,121); groebnerMatrix(54,121) = 0.0; groebnerMatrix(54,129) = groebnerMatrix(54,129) - factor * groebnerMatrix(11,174); groebnerMatrix(54,138) = groebnerMatrix(54,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(54,122); groebnerMatrix(54,122) = 0.0; groebnerMatrix(54,128) = groebnerMatrix(54,128) - factor * groebnerMatrix(21,173); groebnerMatrix(54,180) = groebnerMatrix(54,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(54,123); groebnerMatrix(54,123) = 0.0; groebnerMatrix(54,136) = groebnerMatrix(54,136) - factor * groebnerMatrix(27,181); groebnerMatrix(54,179) = groebnerMatrix(54,179) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(54,124); groebnerMatrix(54,124) = 0.0; groebnerMatrix(54,132) = groebnerMatrix(54,132) - factor * groebnerMatrix(10,177); groebnerMatrix(54,141) = groebnerMatrix(54,141) - factor * groebnerMatrix(10,186); groebnerMatrix(54,195) = groebnerMatrix(54,195) - factor * groebnerMatrix(10,196); groebnerRow46_000000000_f(groebnerMatrix,54); groebnerRow47_000000000_f(groebnerMatrix,54); factor = groebnerMatrix(54,127); groebnerMatrix(54,127) = 0.0; groebnerMatrix(54,134) = groebnerMatrix(54,134) - factor * groebnerMatrix(17,179); groebnerMatrix(54,181) = groebnerMatrix(54,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,54); groebnerRow49_000000000_f(groebnerMatrix,54); factor = -groebnerMatrix(54,130); groebnerMatrix(54,130) = 0.0; groebnerMatrix(54,137) = groebnerMatrix(54,137) - factor * groebnerMatrix(18,182); groebnerMatrix(54,178) = groebnerMatrix(54,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,54); groebnerRow51_000000000_f(groebnerMatrix,54); groebnerRow52_000000000_f(groebnerMatrix,54); groebnerRow53_000000000_f(groebnerMatrix,54); factor = groebnerMatrix(54,142); groebnerMatrix(54,142) = 0.0; groebnerMatrix(54,144) = groebnerMatrix(54,144) - factor * groebnerMatrix(15,144); groebnerMatrix(54,147) = groebnerMatrix(54,147) - factor * groebnerMatrix(15,147); groebnerMatrix(54,196) = groebnerMatrix(54,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(54,143); groebnerMatrix(54,143) = 0.0; groebnerMatrix(54,155) = groebnerMatrix(54,155) - factor * groebnerMatrix(26,155); groebnerMatrix(54,176) = groebnerMatrix(54,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(54,144); groebnerMatrix(54,144) = 0.0; groebnerMatrix(54,156) = groebnerMatrix(54,156) - factor * groebnerMatrix(25,156); groebnerMatrix(54,177) = groebnerMatrix(54,177) - factor * groebnerMatrix(25,177); groebnerMatrix(54,196) = groebnerMatrix(54,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(54,146); groebnerMatrix(54,146) = 0.0; groebnerMatrix(54,161) = groebnerMatrix(54,161) - factor * groebnerMatrix(23,161); groebnerMatrix(54,185) = groebnerMatrix(54,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(54,147); groebnerMatrix(54,147) = 0.0; groebnerMatrix(54,162) = groebnerMatrix(54,162) - factor * groebnerMatrix(22,162); groebnerMatrix(54,186) = groebnerMatrix(54,186) - factor * groebnerMatrix(22,186); groebnerMatrix(54,196) = groebnerMatrix(54,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(54,148); groebnerMatrix(54,148) = 0.0; groebnerMatrix(54,153) = groebnerMatrix(54,153) - factor * groebnerMatrix(14,153); groebnerMatrix(54,159) = groebnerMatrix(54,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,54); groebnerRow31_000000000_f(groebnerMatrix,54); factor = -groebnerMatrix(54,154); groebnerMatrix(54,154) = 0.0; groebnerMatrix(54,158) = groebnerMatrix(54,158) - factor * groebnerMatrix(16,158); groebnerMatrix(54,193) = groebnerMatrix(54,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,54); groebnerRow33_000000000_f(groebnerMatrix,54); groebnerRow34_000000000_f(groebnerMatrix,54); groebnerRow35_000000000_f(groebnerMatrix,54); groebnerRow36_000000000_f(groebnerMatrix,54); groebnerRow37_000000000_f(groebnerMatrix,54); groebnerRow38_000000000_f(groebnerMatrix,54); groebnerRow39_000000000_f(groebnerMatrix,54); factor = groebnerMatrix(54,163); groebnerMatrix(54,163) = 0.0; groebnerMatrix(54,171) = groebnerMatrix(54,171) - factor * groebnerMatrix(12,171); groebnerMatrix(54,180) = groebnerMatrix(54,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(54,164); groebnerMatrix(54,164) = 0.0; groebnerMatrix(54,170) = groebnerMatrix(54,170) - factor * groebnerMatrix(20,170); groebnerMatrix(54,192) = groebnerMatrix(54,192) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(54,165); groebnerMatrix(54,165) = 0.0; groebnerMatrix(54,178) = groebnerMatrix(54,178) - factor * groebnerMatrix(29,178); groebnerMatrix(54,191) = groebnerMatrix(54,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(54,166); groebnerMatrix(54,166) = 0.0; groebnerMatrix(54,174) = groebnerMatrix(54,174) - factor * groebnerMatrix(11,174); groebnerMatrix(54,183) = groebnerMatrix(54,183) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(54,167); groebnerMatrix(54,167) = 0.0; groebnerMatrix(54,173) = groebnerMatrix(54,173) - factor * groebnerMatrix(21,173); groebnerMatrix(54,189) = groebnerMatrix(54,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(54,168); groebnerMatrix(54,168) = 0.0; groebnerMatrix(54,181) = groebnerMatrix(54,181) - factor * groebnerMatrix(27,181); groebnerMatrix(54,188) = groebnerMatrix(54,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(54,169); groebnerMatrix(54,169) = 0.0; groebnerMatrix(54,177) = groebnerMatrix(54,177) - factor * groebnerMatrix(10,177); groebnerMatrix(54,186) = groebnerMatrix(54,186) - factor * groebnerMatrix(10,186); groebnerMatrix(54,196) = groebnerMatrix(54,196) - factor * groebnerMatrix(10,196); factor = groebnerMatrix(54,172); groebnerMatrix(54,172) = 0.0; groebnerMatrix(54,179) = groebnerMatrix(54,179) - factor * groebnerMatrix(17,179); groebnerMatrix(54,190) = groebnerMatrix(54,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(54,175); groebnerMatrix(54,175) = 0.0; groebnerMatrix(54,182) = groebnerMatrix(54,182) - factor * groebnerMatrix(18,182); groebnerMatrix(54,187) = groebnerMatrix(54,187) - factor * groebnerMatrix(18,187); sPolynomial55(groebnerMatrix); groebnerRow39_000100000_f(groebnerMatrix,55); groebnerRow30_010000000_f(groebnerMatrix,55); groebnerRow31_010000000_f(groebnerMatrix,55); groebnerRow32_010000000_f(groebnerMatrix,55); groebnerRow33_010000000_f(groebnerMatrix,55); factor = -groebnerMatrix(55,76); groebnerMatrix(55,76) = 0.0; groebnerMatrix(55,107) = groebnerMatrix(55,107) - factor * groebnerMatrix(18,182); groebnerMatrix(55,142) = groebnerMatrix(55,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(55,77); groebnerMatrix(55,77) = 0.0; groebnerMatrix(55,108) = groebnerMatrix(55,108) - factor * groebnerMatrix(18,182); groebnerMatrix(55,143) = groebnerMatrix(55,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(55,78); groebnerMatrix(55,78) = 0.0; groebnerMatrix(55,113) = groebnerMatrix(55,113) - factor * groebnerMatrix(17,179); groebnerMatrix(55,160) = groebnerMatrix(55,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(55,79); groebnerMatrix(55,79) = 0.0; groebnerMatrix(55,110) = groebnerMatrix(55,110) - factor * groebnerMatrix(18,182); groebnerMatrix(55,148) = groebnerMatrix(55,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(55,80); groebnerMatrix(55,80) = 0.0; groebnerMatrix(55,111) = groebnerMatrix(55,111) - factor * groebnerMatrix(18,182); groebnerMatrix(55,152) = groebnerMatrix(55,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(55,81); groebnerMatrix(55,81) = 0.0; groebnerMatrix(55,116) = groebnerMatrix(55,116) - factor * groebnerMatrix(18,182); groebnerMatrix(55,157) = groebnerMatrix(55,157) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(55,86); groebnerMatrix(55,86) = 0.0; groebnerMatrix(55,92) = groebnerMatrix(55,92) - factor * groebnerMatrix(21,173); groebnerMatrix(55,172) = groebnerMatrix(55,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(55,87); groebnerMatrix(55,87) = 0.0; groebnerMatrix(55,122) = groebnerMatrix(55,122) - factor * groebnerMatrix(18,182); groebnerMatrix(55,163) = groebnerMatrix(55,163) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,55); groebnerRow41_000000000_f(groebnerMatrix,55); groebnerRow42_000000000_f(groebnerMatrix,55); groebnerRow43_000000000_f(groebnerMatrix,55); factor = -groebnerMatrix(55,94); groebnerMatrix(55,94) = 0.0; groebnerMatrix(55,129) = groebnerMatrix(55,129) - factor * groebnerMatrix(18,182); groebnerMatrix(55,170) = groebnerMatrix(55,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,55); groebnerRow45_000000000_f(groebnerMatrix,55); groebnerRow30_100000000_f(groebnerMatrix,55); groebnerRow31_100000000_f(groebnerMatrix,55); factor = -groebnerMatrix(55,109); groebnerMatrix(55,109) = 0.0; groebnerMatrix(55,113) = groebnerMatrix(55,113) - factor * groebnerMatrix(16,158); groebnerMatrix(55,184) = groebnerMatrix(55,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,55); groebnerRow33_100000000_f(groebnerMatrix,55); groebnerRow34_100000000_f(groebnerMatrix,55); groebnerRow35_100000000_f(groebnerMatrix,55); groebnerRow36_100000000_f(groebnerMatrix,55); groebnerRow37_100000000_f(groebnerMatrix,55); groebnerRow38_100000000_f(groebnerMatrix,55); groebnerRow39_100000000_f(groebnerMatrix,55); factor = -groebnerMatrix(55,122); groebnerMatrix(55,122) = 0.0; groebnerMatrix(55,128) = groebnerMatrix(55,128) - factor * groebnerMatrix(21,173); groebnerMatrix(55,180) = groebnerMatrix(55,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(55,123); groebnerMatrix(55,123) = 0.0; groebnerMatrix(55,136) = groebnerMatrix(55,136) - factor * groebnerMatrix(27,181); groebnerMatrix(55,179) = groebnerMatrix(55,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,55); groebnerRow47_000000000_f(groebnerMatrix,55); factor = groebnerMatrix(55,127); groebnerMatrix(55,127) = 0.0; groebnerMatrix(55,134) = groebnerMatrix(55,134) - factor * groebnerMatrix(17,179); groebnerMatrix(55,181) = groebnerMatrix(55,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,55); groebnerRow49_000000000_f(groebnerMatrix,55); factor = -groebnerMatrix(55,130); groebnerMatrix(55,130) = 0.0; groebnerMatrix(55,137) = groebnerMatrix(55,137) - factor * groebnerMatrix(18,182); groebnerMatrix(55,178) = groebnerMatrix(55,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,55); groebnerRow51_000000000_f(groebnerMatrix,55); groebnerRow52_000000000_f(groebnerMatrix,55); groebnerRow53_000000000_f(groebnerMatrix,55); groebnerRow54_000000000_f(groebnerMatrix,55); factor = groebnerMatrix(55,142); groebnerMatrix(55,142) = 0.0; groebnerMatrix(55,144) = groebnerMatrix(55,144) - factor * groebnerMatrix(15,144); groebnerMatrix(55,147) = groebnerMatrix(55,147) - factor * groebnerMatrix(15,147); groebnerMatrix(55,196) = groebnerMatrix(55,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(55,143); groebnerMatrix(55,143) = 0.0; groebnerMatrix(55,155) = groebnerMatrix(55,155) - factor * groebnerMatrix(26,155); groebnerMatrix(55,176) = groebnerMatrix(55,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(55,144); groebnerMatrix(55,144) = 0.0; groebnerMatrix(55,156) = groebnerMatrix(55,156) - factor * groebnerMatrix(25,156); groebnerMatrix(55,177) = groebnerMatrix(55,177) - factor * groebnerMatrix(25,177); groebnerMatrix(55,196) = groebnerMatrix(55,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(55,147); groebnerMatrix(55,147) = 0.0; groebnerMatrix(55,162) = groebnerMatrix(55,162) - factor * groebnerMatrix(22,162); groebnerMatrix(55,186) = groebnerMatrix(55,186) - factor * groebnerMatrix(22,186); groebnerMatrix(55,196) = groebnerMatrix(55,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(55,148); groebnerMatrix(55,148) = 0.0; groebnerMatrix(55,153) = groebnerMatrix(55,153) - factor * groebnerMatrix(14,153); groebnerMatrix(55,159) = groebnerMatrix(55,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,55); groebnerRow31_000000000_f(groebnerMatrix,55); factor = -groebnerMatrix(55,154); groebnerMatrix(55,154) = 0.0; groebnerMatrix(55,158) = groebnerMatrix(55,158) - factor * groebnerMatrix(16,158); groebnerMatrix(55,193) = groebnerMatrix(55,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,55); groebnerRow33_000000000_f(groebnerMatrix,55); groebnerRow34_000000000_f(groebnerMatrix,55); groebnerRow35_000000000_f(groebnerMatrix,55); groebnerRow36_000000000_f(groebnerMatrix,55); groebnerRow37_000000000_f(groebnerMatrix,55); groebnerRow38_000000000_f(groebnerMatrix,55); groebnerRow39_000000000_f(groebnerMatrix,55); factor = groebnerMatrix(55,163); groebnerMatrix(55,163) = 0.0; groebnerMatrix(55,171) = groebnerMatrix(55,171) - factor * groebnerMatrix(12,171); groebnerMatrix(55,180) = groebnerMatrix(55,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(55,167); groebnerMatrix(55,167) = 0.0; groebnerMatrix(55,173) = groebnerMatrix(55,173) - factor * groebnerMatrix(21,173); groebnerMatrix(55,189) = groebnerMatrix(55,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(55,168); groebnerMatrix(55,168) = 0.0; groebnerMatrix(55,181) = groebnerMatrix(55,181) - factor * groebnerMatrix(27,181); groebnerMatrix(55,188) = groebnerMatrix(55,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(55,172); groebnerMatrix(55,172) = 0.0; groebnerMatrix(55,179) = groebnerMatrix(55,179) - factor * groebnerMatrix(17,179); groebnerMatrix(55,190) = groebnerMatrix(55,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(55,175); groebnerMatrix(55,175) = 0.0; groebnerMatrix(55,182) = groebnerMatrix(55,182) - factor * groebnerMatrix(18,182); groebnerMatrix(55,187) = groebnerMatrix(55,187) - factor * groebnerMatrix(18,187); sPolynomial56(groebnerMatrix); groebnerRow38_000100000_f(groebnerMatrix,56); groebnerRow39_000100000_f(groebnerMatrix,56); factor = groebnerMatrix(56,67); groebnerMatrix(56,67) = 0.0; groebnerMatrix(56,72) = groebnerMatrix(56,72) - factor * groebnerMatrix(14,153); groebnerMatrix(56,78) = groebnerMatrix(56,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(56,68); groebnerMatrix(56,68) = 0.0; groebnerMatrix(56,71) = groebnerMatrix(56,71) - factor * groebnerMatrix(19,152); groebnerMatrix(56,185) = groebnerMatrix(56,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(56,70); groebnerMatrix(56,70) = 0.0; groebnerMatrix(56,75) = groebnerMatrix(56,75) - factor * groebnerMatrix(13,156); groebnerMatrix(56,81) = groebnerMatrix(56,81) - factor * groebnerMatrix(13,162); groebnerMatrix(56,194) = groebnerMatrix(56,194) - factor * groebnerMatrix(13,196); groebnerRow30_010000000_f(groebnerMatrix,56); groebnerRow31_010000000_f(groebnerMatrix,56); groebnerRow32_010000000_f(groebnerMatrix,56); groebnerRow33_010000000_f(groebnerMatrix,56); factor = -groebnerMatrix(56,76); groebnerMatrix(56,76) = 0.0; groebnerMatrix(56,107) = groebnerMatrix(56,107) - factor * groebnerMatrix(18,182); groebnerMatrix(56,142) = groebnerMatrix(56,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(56,77); groebnerMatrix(56,77) = 0.0; groebnerMatrix(56,108) = groebnerMatrix(56,108) - factor * groebnerMatrix(18,182); groebnerMatrix(56,143) = groebnerMatrix(56,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(56,78); groebnerMatrix(56,78) = 0.0; groebnerMatrix(56,113) = groebnerMatrix(56,113) - factor * groebnerMatrix(17,179); groebnerMatrix(56,160) = groebnerMatrix(56,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(56,79); groebnerMatrix(56,79) = 0.0; groebnerMatrix(56,110) = groebnerMatrix(56,110) - factor * groebnerMatrix(18,182); groebnerMatrix(56,148) = groebnerMatrix(56,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(56,80); groebnerMatrix(56,80) = 0.0; groebnerMatrix(56,111) = groebnerMatrix(56,111) - factor * groebnerMatrix(18,182); groebnerMatrix(56,152) = groebnerMatrix(56,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(56,81); groebnerMatrix(56,81) = 0.0; groebnerMatrix(56,116) = groebnerMatrix(56,116) - factor * groebnerMatrix(18,182); groebnerMatrix(56,157) = groebnerMatrix(56,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(56,85); groebnerMatrix(56,85) = 0.0; groebnerMatrix(56,93) = groebnerMatrix(56,93) - factor * groebnerMatrix(11,174); groebnerMatrix(56,130) = groebnerMatrix(56,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(56,87); groebnerMatrix(56,87) = 0.0; groebnerMatrix(56,122) = groebnerMatrix(56,122) - factor * groebnerMatrix(18,182); groebnerMatrix(56,163) = groebnerMatrix(56,163) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,56); groebnerRow41_000000000_f(groebnerMatrix,56); groebnerRow42_000000000_f(groebnerMatrix,56); groebnerRow43_000000000_f(groebnerMatrix,56); factor = -groebnerMatrix(56,94); groebnerMatrix(56,94) = 0.0; groebnerMatrix(56,129) = groebnerMatrix(56,129) - factor * groebnerMatrix(18,182); groebnerMatrix(56,170) = groebnerMatrix(56,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,56); groebnerRow45_000000000_f(groebnerMatrix,56); factor = groebnerMatrix(56,103); groebnerMatrix(56,103) = 0.0; groebnerMatrix(56,108) = groebnerMatrix(56,108) - factor * groebnerMatrix(14,153); groebnerMatrix(56,114) = groebnerMatrix(56,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(56,104); groebnerMatrix(56,104) = 0.0; groebnerMatrix(56,107) = groebnerMatrix(56,107) - factor * groebnerMatrix(19,152); groebnerMatrix(56,186) = groebnerMatrix(56,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(56,105); groebnerMatrix(56,105) = 0.0; groebnerMatrix(56,112) = groebnerMatrix(56,112) - factor * groebnerMatrix(28,157); groebnerMatrix(56,185) = groebnerMatrix(56,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(56,106); groebnerMatrix(56,106) = 0.0; groebnerMatrix(56,111) = groebnerMatrix(56,111) - factor * groebnerMatrix(13,156); groebnerMatrix(56,117) = groebnerMatrix(56,117) - factor * groebnerMatrix(13,162); groebnerMatrix(56,195) = groebnerMatrix(56,195) - factor * groebnerMatrix(13,196); groebnerRow30_100000000_f(groebnerMatrix,56); groebnerRow31_100000000_f(groebnerMatrix,56); groebnerRow32_100000000_f(groebnerMatrix,56); groebnerRow33_100000000_f(groebnerMatrix,56); groebnerRow34_100000000_f(groebnerMatrix,56); groebnerRow35_100000000_f(groebnerMatrix,56); groebnerRow36_100000000_f(groebnerMatrix,56); groebnerRow37_100000000_f(groebnerMatrix,56); groebnerRow38_100000000_f(groebnerMatrix,56); groebnerRow39_100000000_f(groebnerMatrix,56); factor = groebnerMatrix(56,121); groebnerMatrix(56,121) = 0.0; groebnerMatrix(56,129) = groebnerMatrix(56,129) - factor * groebnerMatrix(11,174); groebnerMatrix(56,138) = groebnerMatrix(56,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(56,122); groebnerMatrix(56,122) = 0.0; groebnerMatrix(56,128) = groebnerMatrix(56,128) - factor * groebnerMatrix(21,173); groebnerMatrix(56,180) = groebnerMatrix(56,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(56,123); groebnerMatrix(56,123) = 0.0; groebnerMatrix(56,136) = groebnerMatrix(56,136) - factor * groebnerMatrix(27,181); groebnerMatrix(56,179) = groebnerMatrix(56,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,56); groebnerRow47_000000000_f(groebnerMatrix,56); factor = groebnerMatrix(56,127); groebnerMatrix(56,127) = 0.0; groebnerMatrix(56,134) = groebnerMatrix(56,134) - factor * groebnerMatrix(17,179); groebnerMatrix(56,181) = groebnerMatrix(56,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,56); groebnerRow49_000000000_f(groebnerMatrix,56); factor = -groebnerMatrix(56,130); groebnerMatrix(56,130) = 0.0; groebnerMatrix(56,137) = groebnerMatrix(56,137) - factor * groebnerMatrix(18,182); groebnerMatrix(56,178) = groebnerMatrix(56,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,56); groebnerRow51_000000000_f(groebnerMatrix,56); groebnerRow52_000000000_f(groebnerMatrix,56); groebnerRow53_000000000_f(groebnerMatrix,56); groebnerRow54_000000000_f(groebnerMatrix,56); groebnerRow55_000000000_f(groebnerMatrix,56); factor = groebnerMatrix(56,142); groebnerMatrix(56,142) = 0.0; groebnerMatrix(56,144) = groebnerMatrix(56,144) - factor * groebnerMatrix(15,144); groebnerMatrix(56,147) = groebnerMatrix(56,147) - factor * groebnerMatrix(15,147); groebnerMatrix(56,196) = groebnerMatrix(56,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(56,143); groebnerMatrix(56,143) = 0.0; groebnerMatrix(56,155) = groebnerMatrix(56,155) - factor * groebnerMatrix(26,155); groebnerMatrix(56,176) = groebnerMatrix(56,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(56,144); groebnerMatrix(56,144) = 0.0; groebnerMatrix(56,156) = groebnerMatrix(56,156) - factor * groebnerMatrix(25,156); groebnerMatrix(56,177) = groebnerMatrix(56,177) - factor * groebnerMatrix(25,177); groebnerMatrix(56,196) = groebnerMatrix(56,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(56,147); groebnerMatrix(56,147) = 0.0; groebnerMatrix(56,162) = groebnerMatrix(56,162) - factor * groebnerMatrix(22,162); groebnerMatrix(56,186) = groebnerMatrix(56,186) - factor * groebnerMatrix(22,186); groebnerMatrix(56,196) = groebnerMatrix(56,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(56,148); groebnerMatrix(56,148) = 0.0; groebnerMatrix(56,153) = groebnerMatrix(56,153) - factor * groebnerMatrix(14,153); groebnerMatrix(56,159) = groebnerMatrix(56,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(56,149); groebnerMatrix(56,149) = 0.0; groebnerMatrix(56,152) = groebnerMatrix(56,152) - factor * groebnerMatrix(19,152); groebnerMatrix(56,195) = groebnerMatrix(56,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(56,150); groebnerMatrix(56,150) = 0.0; groebnerMatrix(56,157) = groebnerMatrix(56,157) - factor * groebnerMatrix(28,157); groebnerMatrix(56,194) = groebnerMatrix(56,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(56,151); groebnerMatrix(56,151) = 0.0; groebnerMatrix(56,156) = groebnerMatrix(56,156) - factor * groebnerMatrix(13,156); groebnerMatrix(56,162) = groebnerMatrix(56,162) - factor * groebnerMatrix(13,162); groebnerMatrix(56,196) = groebnerMatrix(56,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,56); groebnerRow31_000000000_f(groebnerMatrix,56); groebnerRow32_000000000_f(groebnerMatrix,56); groebnerRow33_000000000_f(groebnerMatrix,56); groebnerRow34_000000000_f(groebnerMatrix,56); groebnerRow35_000000000_f(groebnerMatrix,56); groebnerRow36_000000000_f(groebnerMatrix,56); groebnerRow37_000000000_f(groebnerMatrix,56); groebnerRow38_000000000_f(groebnerMatrix,56); groebnerRow39_000000000_f(groebnerMatrix,56); factor = groebnerMatrix(56,163); groebnerMatrix(56,163) = 0.0; groebnerMatrix(56,171) = groebnerMatrix(56,171) - factor * groebnerMatrix(12,171); groebnerMatrix(56,180) = groebnerMatrix(56,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(56,166); groebnerMatrix(56,166) = 0.0; groebnerMatrix(56,174) = groebnerMatrix(56,174) - factor * groebnerMatrix(11,174); groebnerMatrix(56,183) = groebnerMatrix(56,183) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(56,168); groebnerMatrix(56,168) = 0.0; groebnerMatrix(56,181) = groebnerMatrix(56,181) - factor * groebnerMatrix(27,181); groebnerMatrix(56,188) = groebnerMatrix(56,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(56,172); groebnerMatrix(56,172) = 0.0; groebnerMatrix(56,179) = groebnerMatrix(56,179) - factor * groebnerMatrix(17,179); groebnerMatrix(56,190) = groebnerMatrix(56,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(56,175); groebnerMatrix(56,175) = 0.0; groebnerMatrix(56,182) = groebnerMatrix(56,182) - factor * groebnerMatrix(18,182); groebnerMatrix(56,187) = groebnerMatrix(56,187) - factor * groebnerMatrix(18,187); sPolynomial57(groebnerMatrix); groebnerRow37_000100000_f(groebnerMatrix,57); groebnerRow38_000100000_f(groebnerMatrix,57); groebnerRow39_000100000_f(groebnerMatrix,57); factor = groebnerMatrix(57,64); groebnerMatrix(57,64) = 0.0; groebnerMatrix(57,98) = groebnerMatrix(57,98) - factor * groebnerMatrix(17,179); groebnerMatrix(57,148) = groebnerMatrix(57,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(57,65); groebnerMatrix(57,65) = 0.0; groebnerMatrix(57,99) = groebnerMatrix(57,99) - factor * groebnerMatrix(17,179); groebnerMatrix(57,149) = groebnerMatrix(57,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(57,69); groebnerMatrix(57,69) = 0.0; groebnerMatrix(57,104) = groebnerMatrix(57,104) - factor * groebnerMatrix(17,179); groebnerMatrix(57,151) = groebnerMatrix(57,151) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(57,73); groebnerMatrix(57,73) = 0.0; groebnerMatrix(57,77) = groebnerMatrix(57,77) - factor * groebnerMatrix(16,158); groebnerMatrix(57,176) = groebnerMatrix(57,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(57,76); groebnerMatrix(57,76) = 0.0; groebnerMatrix(57,107) = groebnerMatrix(57,107) - factor * groebnerMatrix(18,182); groebnerMatrix(57,142) = groebnerMatrix(57,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(57,77); groebnerMatrix(57,77) = 0.0; groebnerMatrix(57,108) = groebnerMatrix(57,108) - factor * groebnerMatrix(18,182); groebnerMatrix(57,143) = groebnerMatrix(57,143) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(57,79); groebnerMatrix(57,79) = 0.0; groebnerMatrix(57,110) = groebnerMatrix(57,110) - factor * groebnerMatrix(18,182); groebnerMatrix(57,148) = groebnerMatrix(57,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(57,80); groebnerMatrix(57,80) = 0.0; groebnerMatrix(57,111) = groebnerMatrix(57,111) - factor * groebnerMatrix(18,182); groebnerMatrix(57,152) = groebnerMatrix(57,152) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(57,84); groebnerMatrix(57,84) = 0.0; groebnerMatrix(57,119) = groebnerMatrix(57,119) - factor * groebnerMatrix(17,179); groebnerMatrix(57,166) = groebnerMatrix(57,166) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(57,87); groebnerMatrix(57,87) = 0.0; groebnerMatrix(57,122) = groebnerMatrix(57,122) - factor * groebnerMatrix(18,182); groebnerMatrix(57,163) = groebnerMatrix(57,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(57,91); groebnerMatrix(57,91) = 0.0; groebnerMatrix(57,126) = groebnerMatrix(57,126) - factor * groebnerMatrix(17,179); groebnerMatrix(57,173) = groebnerMatrix(57,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(57,94); groebnerMatrix(57,94) = 0.0; groebnerMatrix(57,129) = groebnerMatrix(57,129) - factor * groebnerMatrix(18,182); groebnerMatrix(57,170) = groebnerMatrix(57,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(57,98); groebnerMatrix(57,98) = 0.0; groebnerMatrix(57,110) = groebnerMatrix(57,110) - factor * groebnerMatrix(26,155); groebnerMatrix(57,131) = groebnerMatrix(57,131) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(57,99); groebnerMatrix(57,99) = 0.0; groebnerMatrix(57,111) = groebnerMatrix(57,111) - factor * groebnerMatrix(25,156); groebnerMatrix(57,132) = groebnerMatrix(57,132) - factor * groebnerMatrix(25,177); groebnerMatrix(57,195) = groebnerMatrix(57,195) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(57,100); groebnerMatrix(57,100) = 0.0; groebnerMatrix(57,115) = groebnerMatrix(57,115) - factor * groebnerMatrix(24,160); groebnerMatrix(57,139) = groebnerMatrix(57,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(57,101); groebnerMatrix(57,101) = 0.0; groebnerMatrix(57,116) = groebnerMatrix(57,116) - factor * groebnerMatrix(23,161); groebnerMatrix(57,140) = groebnerMatrix(57,140) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(57,102); groebnerMatrix(57,102) = 0.0; groebnerMatrix(57,117) = groebnerMatrix(57,117) - factor * groebnerMatrix(22,162); groebnerMatrix(57,141) = groebnerMatrix(57,141) - factor * groebnerMatrix(22,186); groebnerMatrix(57,195) = groebnerMatrix(57,195) - factor * groebnerMatrix(22,196); factor = -groebnerMatrix(57,104); groebnerMatrix(57,104) = 0.0; groebnerMatrix(57,107) = groebnerMatrix(57,107) - factor * groebnerMatrix(19,152); groebnerMatrix(57,186) = groebnerMatrix(57,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(57,105); groebnerMatrix(57,105) = 0.0; groebnerMatrix(57,112) = groebnerMatrix(57,112) - factor * groebnerMatrix(28,157); groebnerMatrix(57,185) = groebnerMatrix(57,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,57); groebnerRow31_100000000_f(groebnerMatrix,57); factor = -groebnerMatrix(57,109); groebnerMatrix(57,109) = 0.0; groebnerMatrix(57,113) = groebnerMatrix(57,113) - factor * groebnerMatrix(16,158); groebnerMatrix(57,184) = groebnerMatrix(57,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,57); groebnerRow33_100000000_f(groebnerMatrix,57); groebnerRow34_100000000_f(groebnerMatrix,57); groebnerRow35_100000000_f(groebnerMatrix,57); groebnerRow36_100000000_f(groebnerMatrix,57); groebnerRow37_100000000_f(groebnerMatrix,57); groebnerRow38_100000000_f(groebnerMatrix,57); groebnerRow39_100000000_f(groebnerMatrix,57); factor = groebnerMatrix(57,119); groebnerMatrix(57,119) = 0.0; groebnerMatrix(57,125) = groebnerMatrix(57,125) - factor * groebnerMatrix(20,170); groebnerMatrix(57,183) = groebnerMatrix(57,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(57,120); groebnerMatrix(57,120) = 0.0; groebnerMatrix(57,133) = groebnerMatrix(57,133) - factor * groebnerMatrix(29,178); groebnerMatrix(57,182) = groebnerMatrix(57,182) - factor * groebnerMatrix(29,191); factor = -groebnerMatrix(57,122); groebnerMatrix(57,122) = 0.0; groebnerMatrix(57,128) = groebnerMatrix(57,128) - factor * groebnerMatrix(21,173); groebnerMatrix(57,180) = groebnerMatrix(57,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(57,123); groebnerMatrix(57,123) = 0.0; groebnerMatrix(57,136) = groebnerMatrix(57,136) - factor * groebnerMatrix(27,181); groebnerMatrix(57,179) = groebnerMatrix(57,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,57); groebnerRow47_000000000_f(groebnerMatrix,57); factor = groebnerMatrix(57,127); groebnerMatrix(57,127) = 0.0; groebnerMatrix(57,134) = groebnerMatrix(57,134) - factor * groebnerMatrix(17,179); groebnerMatrix(57,181) = groebnerMatrix(57,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,57); groebnerRow49_000000000_f(groebnerMatrix,57); factor = -groebnerMatrix(57,130); groebnerMatrix(57,130) = 0.0; groebnerMatrix(57,137) = groebnerMatrix(57,137) - factor * groebnerMatrix(18,182); groebnerMatrix(57,178) = groebnerMatrix(57,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,57); groebnerRow51_000000000_f(groebnerMatrix,57); groebnerRow52_000000000_f(groebnerMatrix,57); groebnerRow53_000000000_f(groebnerMatrix,57); groebnerRow54_000000000_f(groebnerMatrix,57); groebnerRow55_000000000_f(groebnerMatrix,57); groebnerRow56_000000000_f(groebnerMatrix,57); factor = groebnerMatrix(57,142); groebnerMatrix(57,142) = 0.0; groebnerMatrix(57,144) = groebnerMatrix(57,144) - factor * groebnerMatrix(15,144); groebnerMatrix(57,147) = groebnerMatrix(57,147) - factor * groebnerMatrix(15,147); groebnerMatrix(57,196) = groebnerMatrix(57,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(57,143); groebnerMatrix(57,143) = 0.0; groebnerMatrix(57,155) = groebnerMatrix(57,155) - factor * groebnerMatrix(26,155); groebnerMatrix(57,176) = groebnerMatrix(57,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(57,144); groebnerMatrix(57,144) = 0.0; groebnerMatrix(57,156) = groebnerMatrix(57,156) - factor * groebnerMatrix(25,156); groebnerMatrix(57,177) = groebnerMatrix(57,177) - factor * groebnerMatrix(25,177); groebnerMatrix(57,196) = groebnerMatrix(57,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(57,145); groebnerMatrix(57,145) = 0.0; groebnerMatrix(57,160) = groebnerMatrix(57,160) - factor * groebnerMatrix(24,160); groebnerMatrix(57,184) = groebnerMatrix(57,184) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(57,146); groebnerMatrix(57,146) = 0.0; groebnerMatrix(57,161) = groebnerMatrix(57,161) - factor * groebnerMatrix(23,161); groebnerMatrix(57,185) = groebnerMatrix(57,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(57,147); groebnerMatrix(57,147) = 0.0; groebnerMatrix(57,162) = groebnerMatrix(57,162) - factor * groebnerMatrix(22,162); groebnerMatrix(57,186) = groebnerMatrix(57,186) - factor * groebnerMatrix(22,186); groebnerMatrix(57,196) = groebnerMatrix(57,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(57,148); groebnerMatrix(57,148) = 0.0; groebnerMatrix(57,153) = groebnerMatrix(57,153) - factor * groebnerMatrix(14,153); groebnerMatrix(57,159) = groebnerMatrix(57,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(57,149); groebnerMatrix(57,149) = 0.0; groebnerMatrix(57,152) = groebnerMatrix(57,152) - factor * groebnerMatrix(19,152); groebnerMatrix(57,195) = groebnerMatrix(57,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(57,150); groebnerMatrix(57,150) = 0.0; groebnerMatrix(57,157) = groebnerMatrix(57,157) - factor * groebnerMatrix(28,157); groebnerMatrix(57,194) = groebnerMatrix(57,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(57,151); groebnerMatrix(57,151) = 0.0; groebnerMatrix(57,156) = groebnerMatrix(57,156) - factor * groebnerMatrix(13,156); groebnerMatrix(57,162) = groebnerMatrix(57,162) - factor * groebnerMatrix(13,162); groebnerMatrix(57,196) = groebnerMatrix(57,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,57); groebnerRow31_000000000_f(groebnerMatrix,57); factor = -groebnerMatrix(57,154); groebnerMatrix(57,154) = 0.0; groebnerMatrix(57,158) = groebnerMatrix(57,158) - factor * groebnerMatrix(16,158); groebnerMatrix(57,193) = groebnerMatrix(57,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,57); groebnerRow33_000000000_f(groebnerMatrix,57); groebnerRow34_000000000_f(groebnerMatrix,57); groebnerRow35_000000000_f(groebnerMatrix,57); groebnerRow36_000000000_f(groebnerMatrix,57); groebnerRow37_000000000_f(groebnerMatrix,57); groebnerRow38_000000000_f(groebnerMatrix,57); groebnerRow39_000000000_f(groebnerMatrix,57); factor = groebnerMatrix(57,163); groebnerMatrix(57,163) = 0.0; groebnerMatrix(57,171) = groebnerMatrix(57,171) - factor * groebnerMatrix(12,171); groebnerMatrix(57,180) = groebnerMatrix(57,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(57,165); groebnerMatrix(57,165) = 0.0; groebnerMatrix(57,178) = groebnerMatrix(57,178) - factor * groebnerMatrix(29,178); groebnerMatrix(57,191) = groebnerMatrix(57,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(57,166); groebnerMatrix(57,166) = 0.0; groebnerMatrix(57,174) = groebnerMatrix(57,174) - factor * groebnerMatrix(11,174); groebnerMatrix(57,183) = groebnerMatrix(57,183) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(57,168); groebnerMatrix(57,168) = 0.0; groebnerMatrix(57,181) = groebnerMatrix(57,181) - factor * groebnerMatrix(27,181); groebnerMatrix(57,188) = groebnerMatrix(57,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(57,172); groebnerMatrix(57,172) = 0.0; groebnerMatrix(57,179) = groebnerMatrix(57,179) - factor * groebnerMatrix(17,179); groebnerMatrix(57,190) = groebnerMatrix(57,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(57,175); groebnerMatrix(57,175) = 0.0; groebnerMatrix(57,182) = groebnerMatrix(57,182) - factor * groebnerMatrix(18,182); groebnerMatrix(57,187) = groebnerMatrix(57,187) - factor * groebnerMatrix(18,187); sPolynomial58(groebnerMatrix); groebnerRow36_000100000_f(groebnerMatrix,58); groebnerRow37_000100000_f(groebnerMatrix,58); groebnerRow38_000100000_f(groebnerMatrix,58); groebnerRow39_000100000_f(groebnerMatrix,58); factor = groebnerMatrix(58,62); groebnerMatrix(58,62) = 0.0; groebnerMatrix(58,74) = groebnerMatrix(58,74) - factor * groebnerMatrix(26,155); groebnerMatrix(58,95) = groebnerMatrix(58,95) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(58,63); groebnerMatrix(58,63) = 0.0; groebnerMatrix(58,75) = groebnerMatrix(58,75) - factor * groebnerMatrix(25,156); groebnerMatrix(58,96) = groebnerMatrix(58,96) - factor * groebnerMatrix(25,177); groebnerMatrix(58,194) = groebnerMatrix(58,194) - factor * groebnerMatrix(25,196); factor = -groebnerMatrix(58,68); groebnerMatrix(58,68) = 0.0; groebnerMatrix(58,71) = groebnerMatrix(58,71) - factor * groebnerMatrix(19,152); groebnerMatrix(58,185) = groebnerMatrix(58,185) - factor * groebnerMatrix(19,195); groebnerRow30_010000000_f(groebnerMatrix,58); groebnerRow31_010000000_f(groebnerMatrix,58); groebnerRow32_010000000_f(groebnerMatrix,58); groebnerRow33_010000000_f(groebnerMatrix,58); factor = -groebnerMatrix(58,76); groebnerMatrix(58,76) = 0.0; groebnerMatrix(58,107) = groebnerMatrix(58,107) - factor * groebnerMatrix(18,182); groebnerMatrix(58,142) = groebnerMatrix(58,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(58,77); groebnerMatrix(58,77) = 0.0; groebnerMatrix(58,108) = groebnerMatrix(58,108) - factor * groebnerMatrix(18,182); groebnerMatrix(58,143) = groebnerMatrix(58,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(58,78); groebnerMatrix(58,78) = 0.0; groebnerMatrix(58,113) = groebnerMatrix(58,113) - factor * groebnerMatrix(17,179); groebnerMatrix(58,160) = groebnerMatrix(58,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(58,79); groebnerMatrix(58,79) = 0.0; groebnerMatrix(58,110) = groebnerMatrix(58,110) - factor * groebnerMatrix(18,182); groebnerMatrix(58,148) = groebnerMatrix(58,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(58,80); groebnerMatrix(58,80) = 0.0; groebnerMatrix(58,111) = groebnerMatrix(58,111) - factor * groebnerMatrix(18,182); groebnerMatrix(58,152) = groebnerMatrix(58,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(58,81); groebnerMatrix(58,81) = 0.0; groebnerMatrix(58,116) = groebnerMatrix(58,116) - factor * groebnerMatrix(18,182); groebnerMatrix(58,157) = groebnerMatrix(58,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(58,83); groebnerMatrix(58,83) = 0.0; groebnerMatrix(58,89) = groebnerMatrix(58,89) - factor * groebnerMatrix(20,170); groebnerMatrix(58,175) = groebnerMatrix(58,175) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(58,87); groebnerMatrix(58,87) = 0.0; groebnerMatrix(58,122) = groebnerMatrix(58,122) - factor * groebnerMatrix(18,182); groebnerMatrix(58,163) = groebnerMatrix(58,163) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,58); groebnerRow41_000000000_f(groebnerMatrix,58); groebnerRow42_000000000_f(groebnerMatrix,58); groebnerRow43_000000000_f(groebnerMatrix,58); factor = -groebnerMatrix(58,94); groebnerMatrix(58,94) = 0.0; groebnerMatrix(58,129) = groebnerMatrix(58,129) - factor * groebnerMatrix(18,182); groebnerMatrix(58,170) = groebnerMatrix(58,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,58); groebnerRow45_000000000_f(groebnerMatrix,58); factor = groebnerMatrix(58,98); groebnerMatrix(58,98) = 0.0; groebnerMatrix(58,110) = groebnerMatrix(58,110) - factor * groebnerMatrix(26,155); groebnerMatrix(58,131) = groebnerMatrix(58,131) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(58,99); groebnerMatrix(58,99) = 0.0; groebnerMatrix(58,111) = groebnerMatrix(58,111) - factor * groebnerMatrix(25,156); groebnerMatrix(58,132) = groebnerMatrix(58,132) - factor * groebnerMatrix(25,177); groebnerMatrix(58,195) = groebnerMatrix(58,195) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(58,101); groebnerMatrix(58,101) = 0.0; groebnerMatrix(58,116) = groebnerMatrix(58,116) - factor * groebnerMatrix(23,161); groebnerMatrix(58,140) = groebnerMatrix(58,140) - factor * groebnerMatrix(23,185); factor = -groebnerMatrix(58,104); groebnerMatrix(58,104) = 0.0; groebnerMatrix(58,107) = groebnerMatrix(58,107) - factor * groebnerMatrix(19,152); groebnerMatrix(58,186) = groebnerMatrix(58,186) - factor * groebnerMatrix(19,195); groebnerRow30_100000000_f(groebnerMatrix,58); groebnerRow31_100000000_f(groebnerMatrix,58); groebnerRow32_100000000_f(groebnerMatrix,58); groebnerRow33_100000000_f(groebnerMatrix,58); groebnerRow34_100000000_f(groebnerMatrix,58); groebnerRow35_100000000_f(groebnerMatrix,58); groebnerRow36_100000000_f(groebnerMatrix,58); groebnerRow37_100000000_f(groebnerMatrix,58); groebnerRow38_100000000_f(groebnerMatrix,58); groebnerRow39_100000000_f(groebnerMatrix,58); factor = groebnerMatrix(58,119); groebnerMatrix(58,119) = 0.0; groebnerMatrix(58,125) = groebnerMatrix(58,125) - factor * groebnerMatrix(20,170); groebnerMatrix(58,183) = groebnerMatrix(58,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(58,122); groebnerMatrix(58,122) = 0.0; groebnerMatrix(58,128) = groebnerMatrix(58,128) - factor * groebnerMatrix(21,173); groebnerMatrix(58,180) = groebnerMatrix(58,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(58,123); groebnerMatrix(58,123) = 0.0; groebnerMatrix(58,136) = groebnerMatrix(58,136) - factor * groebnerMatrix(27,181); groebnerMatrix(58,179) = groebnerMatrix(58,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,58); groebnerRow47_000000000_f(groebnerMatrix,58); factor = groebnerMatrix(58,127); groebnerMatrix(58,127) = 0.0; groebnerMatrix(58,134) = groebnerMatrix(58,134) - factor * groebnerMatrix(17,179); groebnerMatrix(58,181) = groebnerMatrix(58,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,58); groebnerRow49_000000000_f(groebnerMatrix,58); factor = -groebnerMatrix(58,130); groebnerMatrix(58,130) = 0.0; groebnerMatrix(58,137) = groebnerMatrix(58,137) - factor * groebnerMatrix(18,182); groebnerMatrix(58,178) = groebnerMatrix(58,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,58); groebnerRow51_000000000_f(groebnerMatrix,58); groebnerRow52_000000000_f(groebnerMatrix,58); groebnerRow53_000000000_f(groebnerMatrix,58); groebnerRow54_000000000_f(groebnerMatrix,58); groebnerRow55_000000000_f(groebnerMatrix,58); groebnerRow56_000000000_f(groebnerMatrix,58); groebnerRow57_000000000_f(groebnerMatrix,58); factor = groebnerMatrix(58,142); groebnerMatrix(58,142) = 0.0; groebnerMatrix(58,144) = groebnerMatrix(58,144) - factor * groebnerMatrix(15,144); groebnerMatrix(58,147) = groebnerMatrix(58,147) - factor * groebnerMatrix(15,147); groebnerMatrix(58,196) = groebnerMatrix(58,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(58,143); groebnerMatrix(58,143) = 0.0; groebnerMatrix(58,155) = groebnerMatrix(58,155) - factor * groebnerMatrix(26,155); groebnerMatrix(58,176) = groebnerMatrix(58,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(58,144); groebnerMatrix(58,144) = 0.0; groebnerMatrix(58,156) = groebnerMatrix(58,156) - factor * groebnerMatrix(25,156); groebnerMatrix(58,177) = groebnerMatrix(58,177) - factor * groebnerMatrix(25,177); groebnerMatrix(58,196) = groebnerMatrix(58,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(58,146); groebnerMatrix(58,146) = 0.0; groebnerMatrix(58,161) = groebnerMatrix(58,161) - factor * groebnerMatrix(23,161); groebnerMatrix(58,185) = groebnerMatrix(58,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(58,147); groebnerMatrix(58,147) = 0.0; groebnerMatrix(58,162) = groebnerMatrix(58,162) - factor * groebnerMatrix(22,162); groebnerMatrix(58,186) = groebnerMatrix(58,186) - factor * groebnerMatrix(22,186); groebnerMatrix(58,196) = groebnerMatrix(58,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(58,148); groebnerMatrix(58,148) = 0.0; groebnerMatrix(58,153) = groebnerMatrix(58,153) - factor * groebnerMatrix(14,153); groebnerMatrix(58,159) = groebnerMatrix(58,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(58,149); groebnerMatrix(58,149) = 0.0; groebnerMatrix(58,152) = groebnerMatrix(58,152) - factor * groebnerMatrix(19,152); groebnerMatrix(58,195) = groebnerMatrix(58,195) - factor * groebnerMatrix(19,195); groebnerRow30_000000000_f(groebnerMatrix,58); groebnerRow31_000000000_f(groebnerMatrix,58); groebnerRow32_000000000_f(groebnerMatrix,58); groebnerRow33_000000000_f(groebnerMatrix,58); groebnerRow34_000000000_f(groebnerMatrix,58); groebnerRow35_000000000_f(groebnerMatrix,58); groebnerRow36_000000000_f(groebnerMatrix,58); groebnerRow37_000000000_f(groebnerMatrix,58); groebnerRow38_000000000_f(groebnerMatrix,58); groebnerRow39_000000000_f(groebnerMatrix,58); factor = groebnerMatrix(58,163); groebnerMatrix(58,163) = 0.0; groebnerMatrix(58,171) = groebnerMatrix(58,171) - factor * groebnerMatrix(12,171); groebnerMatrix(58,180) = groebnerMatrix(58,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(58,164); groebnerMatrix(58,164) = 0.0; groebnerMatrix(58,170) = groebnerMatrix(58,170) - factor * groebnerMatrix(20,170); groebnerMatrix(58,192) = groebnerMatrix(58,192) - factor * groebnerMatrix(20,192); factor = groebnerMatrix(58,168); groebnerMatrix(58,168) = 0.0; groebnerMatrix(58,181) = groebnerMatrix(58,181) - factor * groebnerMatrix(27,181); groebnerMatrix(58,188) = groebnerMatrix(58,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(58,172); groebnerMatrix(58,172) = 0.0; groebnerMatrix(58,179) = groebnerMatrix(58,179) - factor * groebnerMatrix(17,179); groebnerMatrix(58,190) = groebnerMatrix(58,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(58,175); groebnerMatrix(58,175) = 0.0; groebnerMatrix(58,182) = groebnerMatrix(58,182) - factor * groebnerMatrix(18,182); groebnerMatrix(58,187) = groebnerMatrix(58,187) - factor * groebnerMatrix(18,187); sPolynomial59(groebnerMatrix); groebnerRow35_000100000_f(groebnerMatrix,59); groebnerRow36_000100000_f(groebnerMatrix,59); groebnerRow37_000100000_f(groebnerMatrix,59); groebnerRow38_000100000_f(groebnerMatrix,59); groebnerRow39_000100000_f(groebnerMatrix,59); factor = groebnerMatrix(59,61); groebnerMatrix(59,61) = 0.0; groebnerMatrix(59,63) = groebnerMatrix(59,63) - factor * groebnerMatrix(15,144); groebnerMatrix(59,66) = groebnerMatrix(59,66) - factor * groebnerMatrix(15,147); groebnerMatrix(59,194) = groebnerMatrix(59,194) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(59,62); groebnerMatrix(59,62) = 0.0; groebnerMatrix(59,74) = groebnerMatrix(59,74) - factor * groebnerMatrix(26,155); groebnerMatrix(59,95) = groebnerMatrix(59,95) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(59,63); groebnerMatrix(59,63) = 0.0; groebnerMatrix(59,75) = groebnerMatrix(59,75) - factor * groebnerMatrix(25,156); groebnerMatrix(59,96) = groebnerMatrix(59,96) - factor * groebnerMatrix(25,177); groebnerMatrix(59,194) = groebnerMatrix(59,194) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(59,66); groebnerMatrix(59,66) = 0.0; groebnerMatrix(59,101) = groebnerMatrix(59,101) - factor * groebnerMatrix(17,179); groebnerMatrix(59,150) = groebnerMatrix(59,150) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(59,67); groebnerMatrix(59,67) = 0.0; groebnerMatrix(59,72) = groebnerMatrix(59,72) - factor * groebnerMatrix(14,153); groebnerMatrix(59,78) = groebnerMatrix(59,78) - factor * groebnerMatrix(14,159); groebnerRow30_010000000_f(groebnerMatrix,59); groebnerRow31_010000000_f(groebnerMatrix,59); groebnerRow32_010000000_f(groebnerMatrix,59); groebnerRow33_010000000_f(groebnerMatrix,59); factor = -groebnerMatrix(59,76); groebnerMatrix(59,76) = 0.0; groebnerMatrix(59,107) = groebnerMatrix(59,107) - factor * groebnerMatrix(18,182); groebnerMatrix(59,142) = groebnerMatrix(59,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(59,77); groebnerMatrix(59,77) = 0.0; groebnerMatrix(59,108) = groebnerMatrix(59,108) - factor * groebnerMatrix(18,182); groebnerMatrix(59,143) = groebnerMatrix(59,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(59,78); groebnerMatrix(59,78) = 0.0; groebnerMatrix(59,113) = groebnerMatrix(59,113) - factor * groebnerMatrix(17,179); groebnerMatrix(59,160) = groebnerMatrix(59,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(59,79); groebnerMatrix(59,79) = 0.0; groebnerMatrix(59,110) = groebnerMatrix(59,110) - factor * groebnerMatrix(18,182); groebnerMatrix(59,148) = groebnerMatrix(59,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(59,80); groebnerMatrix(59,80) = 0.0; groebnerMatrix(59,111) = groebnerMatrix(59,111) - factor * groebnerMatrix(18,182); groebnerMatrix(59,152) = groebnerMatrix(59,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(59,81); groebnerMatrix(59,81) = 0.0; groebnerMatrix(59,116) = groebnerMatrix(59,116) - factor * groebnerMatrix(18,182); groebnerMatrix(59,157) = groebnerMatrix(59,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(59,82); groebnerMatrix(59,82) = 0.0; groebnerMatrix(59,90) = groebnerMatrix(59,90) - factor * groebnerMatrix(12,171); groebnerMatrix(59,127) = groebnerMatrix(59,127) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(59,87); groebnerMatrix(59,87) = 0.0; groebnerMatrix(59,122) = groebnerMatrix(59,122) - factor * groebnerMatrix(18,182); groebnerMatrix(59,163) = groebnerMatrix(59,163) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,59); groebnerRow41_000000000_f(groebnerMatrix,59); groebnerRow42_000000000_f(groebnerMatrix,59); groebnerRow43_000000000_f(groebnerMatrix,59); factor = -groebnerMatrix(59,94); groebnerMatrix(59,94) = 0.0; groebnerMatrix(59,129) = groebnerMatrix(59,129) - factor * groebnerMatrix(18,182); groebnerMatrix(59,170) = groebnerMatrix(59,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,59); groebnerRow45_000000000_f(groebnerMatrix,59); factor = groebnerMatrix(59,97); groebnerMatrix(59,97) = 0.0; groebnerMatrix(59,99) = groebnerMatrix(59,99) - factor * groebnerMatrix(15,144); groebnerMatrix(59,102) = groebnerMatrix(59,102) - factor * groebnerMatrix(15,147); groebnerMatrix(59,195) = groebnerMatrix(59,195) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(59,98); groebnerMatrix(59,98) = 0.0; groebnerMatrix(59,110) = groebnerMatrix(59,110) - factor * groebnerMatrix(26,155); groebnerMatrix(59,131) = groebnerMatrix(59,131) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(59,99); groebnerMatrix(59,99) = 0.0; groebnerMatrix(59,111) = groebnerMatrix(59,111) - factor * groebnerMatrix(25,156); groebnerMatrix(59,132) = groebnerMatrix(59,132) - factor * groebnerMatrix(25,177); groebnerMatrix(59,195) = groebnerMatrix(59,195) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(59,100); groebnerMatrix(59,100) = 0.0; groebnerMatrix(59,115) = groebnerMatrix(59,115) - factor * groebnerMatrix(24,160); groebnerMatrix(59,139) = groebnerMatrix(59,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(59,101); groebnerMatrix(59,101) = 0.0; groebnerMatrix(59,116) = groebnerMatrix(59,116) - factor * groebnerMatrix(23,161); groebnerMatrix(59,140) = groebnerMatrix(59,140) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(59,102); groebnerMatrix(59,102) = 0.0; groebnerMatrix(59,117) = groebnerMatrix(59,117) - factor * groebnerMatrix(22,162); groebnerMatrix(59,141) = groebnerMatrix(59,141) - factor * groebnerMatrix(22,186); groebnerMatrix(59,195) = groebnerMatrix(59,195) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(59,103); groebnerMatrix(59,103) = 0.0; groebnerMatrix(59,108) = groebnerMatrix(59,108) - factor * groebnerMatrix(14,153); groebnerMatrix(59,114) = groebnerMatrix(59,114) - factor * groebnerMatrix(14,159); groebnerRow30_100000000_f(groebnerMatrix,59); groebnerRow31_100000000_f(groebnerMatrix,59); groebnerRow32_100000000_f(groebnerMatrix,59); groebnerRow33_100000000_f(groebnerMatrix,59); groebnerRow34_100000000_f(groebnerMatrix,59); groebnerRow35_100000000_f(groebnerMatrix,59); groebnerRow36_100000000_f(groebnerMatrix,59); groebnerRow37_100000000_f(groebnerMatrix,59); groebnerRow38_100000000_f(groebnerMatrix,59); groebnerRow39_100000000_f(groebnerMatrix,59); factor = groebnerMatrix(59,118); groebnerMatrix(59,118) = 0.0; groebnerMatrix(59,126) = groebnerMatrix(59,126) - factor * groebnerMatrix(12,171); groebnerMatrix(59,135) = groebnerMatrix(59,135) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(59,122); groebnerMatrix(59,122) = 0.0; groebnerMatrix(59,128) = groebnerMatrix(59,128) - factor * groebnerMatrix(21,173); groebnerMatrix(59,180) = groebnerMatrix(59,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(59,123); groebnerMatrix(59,123) = 0.0; groebnerMatrix(59,136) = groebnerMatrix(59,136) - factor * groebnerMatrix(27,181); groebnerMatrix(59,179) = groebnerMatrix(59,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,59); groebnerRow47_000000000_f(groebnerMatrix,59); factor = groebnerMatrix(59,127); groebnerMatrix(59,127) = 0.0; groebnerMatrix(59,134) = groebnerMatrix(59,134) - factor * groebnerMatrix(17,179); groebnerMatrix(59,181) = groebnerMatrix(59,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,59); groebnerRow49_000000000_f(groebnerMatrix,59); factor = -groebnerMatrix(59,130); groebnerMatrix(59,130) = 0.0; groebnerMatrix(59,137) = groebnerMatrix(59,137) - factor * groebnerMatrix(18,182); groebnerMatrix(59,178) = groebnerMatrix(59,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,59); groebnerRow51_000000000_f(groebnerMatrix,59); groebnerRow52_000000000_f(groebnerMatrix,59); groebnerRow53_000000000_f(groebnerMatrix,59); groebnerRow54_000000000_f(groebnerMatrix,59); groebnerRow55_000000000_f(groebnerMatrix,59); groebnerRow56_000000000_f(groebnerMatrix,59); groebnerRow57_000000000_f(groebnerMatrix,59); groebnerRow58_000000000_f(groebnerMatrix,59); factor = groebnerMatrix(59,142); groebnerMatrix(59,142) = 0.0; groebnerMatrix(59,144) = groebnerMatrix(59,144) - factor * groebnerMatrix(15,144); groebnerMatrix(59,147) = groebnerMatrix(59,147) - factor * groebnerMatrix(15,147); groebnerMatrix(59,196) = groebnerMatrix(59,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(59,143); groebnerMatrix(59,143) = 0.0; groebnerMatrix(59,155) = groebnerMatrix(59,155) - factor * groebnerMatrix(26,155); groebnerMatrix(59,176) = groebnerMatrix(59,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(59,144); groebnerMatrix(59,144) = 0.0; groebnerMatrix(59,156) = groebnerMatrix(59,156) - factor * groebnerMatrix(25,156); groebnerMatrix(59,177) = groebnerMatrix(59,177) - factor * groebnerMatrix(25,177); groebnerMatrix(59,196) = groebnerMatrix(59,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(59,145); groebnerMatrix(59,145) = 0.0; groebnerMatrix(59,160) = groebnerMatrix(59,160) - factor * groebnerMatrix(24,160); groebnerMatrix(59,184) = groebnerMatrix(59,184) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(59,147); groebnerMatrix(59,147) = 0.0; groebnerMatrix(59,162) = groebnerMatrix(59,162) - factor * groebnerMatrix(22,162); groebnerMatrix(59,186) = groebnerMatrix(59,186) - factor * groebnerMatrix(22,186); groebnerMatrix(59,196) = groebnerMatrix(59,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(59,148); groebnerMatrix(59,148) = 0.0; groebnerMatrix(59,153) = groebnerMatrix(59,153) - factor * groebnerMatrix(14,153); groebnerMatrix(59,159) = groebnerMatrix(59,159) - factor * groebnerMatrix(14,159); factor = groebnerMatrix(59,150); groebnerMatrix(59,150) = 0.0; groebnerMatrix(59,157) = groebnerMatrix(59,157) - factor * groebnerMatrix(28,157); groebnerMatrix(59,194) = groebnerMatrix(59,194) - factor * groebnerMatrix(28,194); groebnerRow30_000000000_f(groebnerMatrix,59); groebnerRow31_000000000_f(groebnerMatrix,59); groebnerRow32_000000000_f(groebnerMatrix,59); groebnerRow33_000000000_f(groebnerMatrix,59); groebnerRow34_000000000_f(groebnerMatrix,59); groebnerRow35_000000000_f(groebnerMatrix,59); groebnerRow36_000000000_f(groebnerMatrix,59); groebnerRow37_000000000_f(groebnerMatrix,59); groebnerRow38_000000000_f(groebnerMatrix,59); groebnerRow39_000000000_f(groebnerMatrix,59); factor = groebnerMatrix(59,163); groebnerMatrix(59,163) = 0.0; groebnerMatrix(59,171) = groebnerMatrix(59,171) - factor * groebnerMatrix(12,171); groebnerMatrix(59,180) = groebnerMatrix(59,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(59,168); groebnerMatrix(59,168) = 0.0; groebnerMatrix(59,181) = groebnerMatrix(59,181) - factor * groebnerMatrix(27,181); groebnerMatrix(59,188) = groebnerMatrix(59,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(59,172); groebnerMatrix(59,172) = 0.0; groebnerMatrix(59,179) = groebnerMatrix(59,179) - factor * groebnerMatrix(17,179); groebnerMatrix(59,190) = groebnerMatrix(59,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(59,175); groebnerMatrix(59,175) = 0.0; groebnerMatrix(59,182) = groebnerMatrix(59,182) - factor * groebnerMatrix(18,182); groebnerMatrix(59,187) = groebnerMatrix(59,187) - factor * groebnerMatrix(18,187); sPolynomial60(groebnerMatrix); groebnerRow34_000100000_f(groebnerMatrix,60); groebnerRow35_000100000_f(groebnerMatrix,60); groebnerRow36_000100000_f(groebnerMatrix,60); groebnerRow37_000100000_f(groebnerMatrix,60); groebnerRow38_000100000_f(groebnerMatrix,60); groebnerRow39_000100000_f(groebnerMatrix,60); groebnerRow30_010000000_f(groebnerMatrix,60); groebnerRow31_010000000_f(groebnerMatrix,60); groebnerRow32_010000000_f(groebnerMatrix,60); groebnerRow33_010000000_f(groebnerMatrix,60); factor = -groebnerMatrix(60,76); groebnerMatrix(60,76) = 0.0; groebnerMatrix(60,107) = groebnerMatrix(60,107) - factor * groebnerMatrix(18,182); groebnerMatrix(60,142) = groebnerMatrix(60,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(60,77); groebnerMatrix(60,77) = 0.0; groebnerMatrix(60,108) = groebnerMatrix(60,108) - factor * groebnerMatrix(18,182); groebnerMatrix(60,143) = groebnerMatrix(60,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(60,78); groebnerMatrix(60,78) = 0.0; groebnerMatrix(60,113) = groebnerMatrix(60,113) - factor * groebnerMatrix(17,179); groebnerMatrix(60,160) = groebnerMatrix(60,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(60,79); groebnerMatrix(60,79) = 0.0; groebnerMatrix(60,110) = groebnerMatrix(60,110) - factor * groebnerMatrix(18,182); groebnerMatrix(60,148) = groebnerMatrix(60,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(60,80); groebnerMatrix(60,80) = 0.0; groebnerMatrix(60,111) = groebnerMatrix(60,111) - factor * groebnerMatrix(18,182); groebnerMatrix(60,152) = groebnerMatrix(60,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(60,81); groebnerMatrix(60,81) = 0.0; groebnerMatrix(60,116) = groebnerMatrix(60,116) - factor * groebnerMatrix(18,182); groebnerMatrix(60,157) = groebnerMatrix(60,157) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(60,86); groebnerMatrix(60,86) = 0.0; groebnerMatrix(60,92) = groebnerMatrix(60,92) - factor * groebnerMatrix(21,173); groebnerMatrix(60,172) = groebnerMatrix(60,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(60,87); groebnerMatrix(60,87) = 0.0; groebnerMatrix(60,122) = groebnerMatrix(60,122) - factor * groebnerMatrix(18,182); groebnerMatrix(60,163) = groebnerMatrix(60,163) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,60); groebnerRow41_000000000_f(groebnerMatrix,60); groebnerRow42_000000000_f(groebnerMatrix,60); groebnerRow43_000000000_f(groebnerMatrix,60); factor = -groebnerMatrix(60,94); groebnerMatrix(60,94) = 0.0; groebnerMatrix(60,129) = groebnerMatrix(60,129) - factor * groebnerMatrix(18,182); groebnerMatrix(60,170) = groebnerMatrix(60,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,60); groebnerRow45_000000000_f(groebnerMatrix,60); groebnerRow30_100000000_f(groebnerMatrix,60); groebnerRow31_100000000_f(groebnerMatrix,60); factor = -groebnerMatrix(60,109); groebnerMatrix(60,109) = 0.0; groebnerMatrix(60,113) = groebnerMatrix(60,113) - factor * groebnerMatrix(16,158); groebnerMatrix(60,184) = groebnerMatrix(60,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,60); groebnerRow33_100000000_f(groebnerMatrix,60); groebnerRow34_100000000_f(groebnerMatrix,60); groebnerRow35_100000000_f(groebnerMatrix,60); groebnerRow36_100000000_f(groebnerMatrix,60); groebnerRow37_100000000_f(groebnerMatrix,60); groebnerRow38_100000000_f(groebnerMatrix,60); groebnerRow39_100000000_f(groebnerMatrix,60); factor = -groebnerMatrix(60,122); groebnerMatrix(60,122) = 0.0; groebnerMatrix(60,128) = groebnerMatrix(60,128) - factor * groebnerMatrix(21,173); groebnerMatrix(60,180) = groebnerMatrix(60,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(60,123); groebnerMatrix(60,123) = 0.0; groebnerMatrix(60,136) = groebnerMatrix(60,136) - factor * groebnerMatrix(27,181); groebnerMatrix(60,179) = groebnerMatrix(60,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,60); groebnerRow47_000000000_f(groebnerMatrix,60); factor = groebnerMatrix(60,127); groebnerMatrix(60,127) = 0.0; groebnerMatrix(60,134) = groebnerMatrix(60,134) - factor * groebnerMatrix(17,179); groebnerMatrix(60,181) = groebnerMatrix(60,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,60); groebnerRow49_000000000_f(groebnerMatrix,60); factor = -groebnerMatrix(60,130); groebnerMatrix(60,130) = 0.0; groebnerMatrix(60,137) = groebnerMatrix(60,137) - factor * groebnerMatrix(18,182); groebnerMatrix(60,178) = groebnerMatrix(60,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,60); groebnerRow51_000000000_f(groebnerMatrix,60); groebnerRow52_000000000_f(groebnerMatrix,60); groebnerRow53_000000000_f(groebnerMatrix,60); groebnerRow54_000000000_f(groebnerMatrix,60); groebnerRow55_000000000_f(groebnerMatrix,60); groebnerRow56_000000000_f(groebnerMatrix,60); groebnerRow57_000000000_f(groebnerMatrix,60); groebnerRow58_000000000_f(groebnerMatrix,60); groebnerRow59_000000000_f(groebnerMatrix,60); factor = groebnerMatrix(60,142); groebnerMatrix(60,142) = 0.0; groebnerMatrix(60,144) = groebnerMatrix(60,144) - factor * groebnerMatrix(15,144); groebnerMatrix(60,147) = groebnerMatrix(60,147) - factor * groebnerMatrix(15,147); groebnerMatrix(60,196) = groebnerMatrix(60,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(60,143); groebnerMatrix(60,143) = 0.0; groebnerMatrix(60,155) = groebnerMatrix(60,155) - factor * groebnerMatrix(26,155); groebnerMatrix(60,176) = groebnerMatrix(60,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(60,144); groebnerMatrix(60,144) = 0.0; groebnerMatrix(60,156) = groebnerMatrix(60,156) - factor * groebnerMatrix(25,156); groebnerMatrix(60,177) = groebnerMatrix(60,177) - factor * groebnerMatrix(25,177); groebnerMatrix(60,196) = groebnerMatrix(60,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(60,147); groebnerMatrix(60,147) = 0.0; groebnerMatrix(60,162) = groebnerMatrix(60,162) - factor * groebnerMatrix(22,162); groebnerMatrix(60,186) = groebnerMatrix(60,186) - factor * groebnerMatrix(22,186); groebnerMatrix(60,196) = groebnerMatrix(60,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(60,148); groebnerMatrix(60,148) = 0.0; groebnerMatrix(60,153) = groebnerMatrix(60,153) - factor * groebnerMatrix(14,153); groebnerMatrix(60,159) = groebnerMatrix(60,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,60); groebnerRow31_000000000_f(groebnerMatrix,60); factor = -groebnerMatrix(60,154); groebnerMatrix(60,154) = 0.0; groebnerMatrix(60,158) = groebnerMatrix(60,158) - factor * groebnerMatrix(16,158); groebnerMatrix(60,193) = groebnerMatrix(60,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,60); groebnerRow33_000000000_f(groebnerMatrix,60); groebnerRow34_000000000_f(groebnerMatrix,60); groebnerRow35_000000000_f(groebnerMatrix,60); groebnerRow36_000000000_f(groebnerMatrix,60); groebnerRow37_000000000_f(groebnerMatrix,60); groebnerRow38_000000000_f(groebnerMatrix,60); groebnerRow39_000000000_f(groebnerMatrix,60); factor = groebnerMatrix(60,163); groebnerMatrix(60,163) = 0.0; groebnerMatrix(60,171) = groebnerMatrix(60,171) - factor * groebnerMatrix(12,171); groebnerMatrix(60,180) = groebnerMatrix(60,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(60,167); groebnerMatrix(60,167) = 0.0; groebnerMatrix(60,173) = groebnerMatrix(60,173) - factor * groebnerMatrix(21,173); groebnerMatrix(60,189) = groebnerMatrix(60,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(60,168); groebnerMatrix(60,168) = 0.0; groebnerMatrix(60,181) = groebnerMatrix(60,181) - factor * groebnerMatrix(27,181); groebnerMatrix(60,188) = groebnerMatrix(60,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(60,172); groebnerMatrix(60,172) = 0.0; groebnerMatrix(60,179) = groebnerMatrix(60,179) - factor * groebnerMatrix(17,179); groebnerMatrix(60,190) = groebnerMatrix(60,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(60,175); groebnerMatrix(60,175) = 0.0; groebnerMatrix(60,182) = groebnerMatrix(60,182) - factor * groebnerMatrix(18,182); groebnerMatrix(60,187) = groebnerMatrix(60,187) - factor * groebnerMatrix(18,187); sPolynomial61(groebnerMatrix); groebnerRow33_000100000_f(groebnerMatrix,61); groebnerRow34_000100000_f(groebnerMatrix,61); groebnerRow35_000100000_f(groebnerMatrix,61); groebnerRow36_000100000_f(groebnerMatrix,61); groebnerRow37_000100000_f(groebnerMatrix,61); groebnerRow38_000100000_f(groebnerMatrix,61); groebnerRow39_000100000_f(groebnerMatrix,61); groebnerRow30_010000000_f(groebnerMatrix,61); groebnerRow31_010000000_f(groebnerMatrix,61); groebnerRow32_010000000_f(groebnerMatrix,61); groebnerRow33_010000000_f(groebnerMatrix,61); factor = -groebnerMatrix(61,76); groebnerMatrix(61,76) = 0.0; groebnerMatrix(61,107) = groebnerMatrix(61,107) - factor * groebnerMatrix(18,182); groebnerMatrix(61,142) = groebnerMatrix(61,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(61,77); groebnerMatrix(61,77) = 0.0; groebnerMatrix(61,108) = groebnerMatrix(61,108) - factor * groebnerMatrix(18,182); groebnerMatrix(61,143) = groebnerMatrix(61,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(61,78); groebnerMatrix(61,78) = 0.0; groebnerMatrix(61,113) = groebnerMatrix(61,113) - factor * groebnerMatrix(17,179); groebnerMatrix(61,160) = groebnerMatrix(61,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(61,79); groebnerMatrix(61,79) = 0.0; groebnerMatrix(61,110) = groebnerMatrix(61,110) - factor * groebnerMatrix(18,182); groebnerMatrix(61,148) = groebnerMatrix(61,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(61,80); groebnerMatrix(61,80) = 0.0; groebnerMatrix(61,111) = groebnerMatrix(61,111) - factor * groebnerMatrix(18,182); groebnerMatrix(61,152) = groebnerMatrix(61,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(61,81); groebnerMatrix(61,81) = 0.0; groebnerMatrix(61,116) = groebnerMatrix(61,116) - factor * groebnerMatrix(18,182); groebnerMatrix(61,157) = groebnerMatrix(61,157) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(61,86); groebnerMatrix(61,86) = 0.0; groebnerMatrix(61,92) = groebnerMatrix(61,92) - factor * groebnerMatrix(21,173); groebnerMatrix(61,172) = groebnerMatrix(61,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(61,87); groebnerMatrix(61,87) = 0.0; groebnerMatrix(61,122) = groebnerMatrix(61,122) - factor * groebnerMatrix(18,182); groebnerMatrix(61,163) = groebnerMatrix(61,163) - factor * groebnerMatrix(18,187); groebnerRow40_000000000_f(groebnerMatrix,61); groebnerRow41_000000000_f(groebnerMatrix,61); groebnerRow42_000000000_f(groebnerMatrix,61); groebnerRow43_000000000_f(groebnerMatrix,61); factor = -groebnerMatrix(61,94); groebnerMatrix(61,94) = 0.0; groebnerMatrix(61,129) = groebnerMatrix(61,129) - factor * groebnerMatrix(18,182); groebnerMatrix(61,170) = groebnerMatrix(61,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,61); groebnerRow45_000000000_f(groebnerMatrix,61); groebnerRow30_100000000_f(groebnerMatrix,61); groebnerRow31_100000000_f(groebnerMatrix,61); factor = -groebnerMatrix(61,109); groebnerMatrix(61,109) = 0.0; groebnerMatrix(61,113) = groebnerMatrix(61,113) - factor * groebnerMatrix(16,158); groebnerMatrix(61,184) = groebnerMatrix(61,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,61); groebnerRow33_100000000_f(groebnerMatrix,61); groebnerRow34_100000000_f(groebnerMatrix,61); groebnerRow35_100000000_f(groebnerMatrix,61); groebnerRow36_100000000_f(groebnerMatrix,61); groebnerRow37_100000000_f(groebnerMatrix,61); groebnerRow38_100000000_f(groebnerMatrix,61); groebnerRow39_100000000_f(groebnerMatrix,61); factor = -groebnerMatrix(61,122); groebnerMatrix(61,122) = 0.0; groebnerMatrix(61,128) = groebnerMatrix(61,128) - factor * groebnerMatrix(21,173); groebnerMatrix(61,180) = groebnerMatrix(61,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(61,123); groebnerMatrix(61,123) = 0.0; groebnerMatrix(61,136) = groebnerMatrix(61,136) - factor * groebnerMatrix(27,181); groebnerMatrix(61,179) = groebnerMatrix(61,179) - factor * groebnerMatrix(27,188); groebnerRow46_000000000_f(groebnerMatrix,61); groebnerRow47_000000000_f(groebnerMatrix,61); factor = groebnerMatrix(61,127); groebnerMatrix(61,127) = 0.0; groebnerMatrix(61,134) = groebnerMatrix(61,134) - factor * groebnerMatrix(17,179); groebnerMatrix(61,181) = groebnerMatrix(61,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,61); groebnerRow49_000000000_f(groebnerMatrix,61); factor = -groebnerMatrix(61,130); groebnerMatrix(61,130) = 0.0; groebnerMatrix(61,137) = groebnerMatrix(61,137) - factor * groebnerMatrix(18,182); groebnerMatrix(61,178) = groebnerMatrix(61,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,61); groebnerRow51_000000000_f(groebnerMatrix,61); groebnerRow52_000000000_f(groebnerMatrix,61); groebnerRow53_000000000_f(groebnerMatrix,61); groebnerRow54_000000000_f(groebnerMatrix,61); groebnerRow55_000000000_f(groebnerMatrix,61); groebnerRow56_000000000_f(groebnerMatrix,61); groebnerRow57_000000000_f(groebnerMatrix,61); groebnerRow58_000000000_f(groebnerMatrix,61); groebnerRow59_000000000_f(groebnerMatrix,61); groebnerRow60_000000000_f(groebnerMatrix,61); factor = groebnerMatrix(61,142); groebnerMatrix(61,142) = 0.0; groebnerMatrix(61,144) = groebnerMatrix(61,144) - factor * groebnerMatrix(15,144); groebnerMatrix(61,147) = groebnerMatrix(61,147) - factor * groebnerMatrix(15,147); groebnerMatrix(61,196) = groebnerMatrix(61,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(61,143); groebnerMatrix(61,143) = 0.0; groebnerMatrix(61,155) = groebnerMatrix(61,155) - factor * groebnerMatrix(26,155); groebnerMatrix(61,176) = groebnerMatrix(61,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(61,144); groebnerMatrix(61,144) = 0.0; groebnerMatrix(61,156) = groebnerMatrix(61,156) - factor * groebnerMatrix(25,156); groebnerMatrix(61,177) = groebnerMatrix(61,177) - factor * groebnerMatrix(25,177); groebnerMatrix(61,196) = groebnerMatrix(61,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(61,147); groebnerMatrix(61,147) = 0.0; groebnerMatrix(61,162) = groebnerMatrix(61,162) - factor * groebnerMatrix(22,162); groebnerMatrix(61,186) = groebnerMatrix(61,186) - factor * groebnerMatrix(22,186); groebnerMatrix(61,196) = groebnerMatrix(61,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(61,148); groebnerMatrix(61,148) = 0.0; groebnerMatrix(61,153) = groebnerMatrix(61,153) - factor * groebnerMatrix(14,153); groebnerMatrix(61,159) = groebnerMatrix(61,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,61); groebnerRow31_000000000_f(groebnerMatrix,61); factor = -groebnerMatrix(61,154); groebnerMatrix(61,154) = 0.0; groebnerMatrix(61,158) = groebnerMatrix(61,158) - factor * groebnerMatrix(16,158); groebnerMatrix(61,193) = groebnerMatrix(61,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,61); groebnerRow33_000000000_f(groebnerMatrix,61); groebnerRow34_000000000_f(groebnerMatrix,61); groebnerRow35_000000000_f(groebnerMatrix,61); groebnerRow36_000000000_f(groebnerMatrix,61); groebnerRow37_000000000_f(groebnerMatrix,61); groebnerRow38_000000000_f(groebnerMatrix,61); groebnerRow39_000000000_f(groebnerMatrix,61); factor = groebnerMatrix(61,163); groebnerMatrix(61,163) = 0.0; groebnerMatrix(61,171) = groebnerMatrix(61,171) - factor * groebnerMatrix(12,171); groebnerMatrix(61,180) = groebnerMatrix(61,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(61,167); groebnerMatrix(61,167) = 0.0; groebnerMatrix(61,173) = groebnerMatrix(61,173) - factor * groebnerMatrix(21,173); groebnerMatrix(61,189) = groebnerMatrix(61,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(61,168); groebnerMatrix(61,168) = 0.0; groebnerMatrix(61,181) = groebnerMatrix(61,181) - factor * groebnerMatrix(27,181); groebnerMatrix(61,188) = groebnerMatrix(61,188) - factor * groebnerMatrix(27,188); factor = groebnerMatrix(61,172); groebnerMatrix(61,172) = 0.0; groebnerMatrix(61,179) = groebnerMatrix(61,179) - factor * groebnerMatrix(17,179); groebnerMatrix(61,190) = groebnerMatrix(61,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(61,175); groebnerMatrix(61,175) = 0.0; groebnerMatrix(61,182) = groebnerMatrix(61,182) - factor * groebnerMatrix(18,182); groebnerMatrix(61,187) = groebnerMatrix(61,187) - factor * groebnerMatrix(18,187); sPolynomial62(groebnerMatrix); groebnerRow33_000100000_f(groebnerMatrix,62); groebnerRow34_000100000_f(groebnerMatrix,62); groebnerRow35_000100000_f(groebnerMatrix,62); groebnerRow36_000100000_f(groebnerMatrix,62); groebnerRow37_000100000_f(groebnerMatrix,62); groebnerRow38_000100000_f(groebnerMatrix,62); groebnerRow39_000100000_f(groebnerMatrix,62); factor = groebnerMatrix(62,67); groebnerMatrix(62,67) = 0.0; groebnerMatrix(62,72) = groebnerMatrix(62,72) - factor * groebnerMatrix(14,153); groebnerMatrix(62,78) = groebnerMatrix(62,78) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(62,68); groebnerMatrix(62,68) = 0.0; groebnerMatrix(62,71) = groebnerMatrix(62,71) - factor * groebnerMatrix(19,152); groebnerMatrix(62,185) = groebnerMatrix(62,185) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(62,70); groebnerMatrix(62,70) = 0.0; groebnerMatrix(62,75) = groebnerMatrix(62,75) - factor * groebnerMatrix(13,156); groebnerMatrix(62,81) = groebnerMatrix(62,81) - factor * groebnerMatrix(13,162); groebnerMatrix(62,194) = groebnerMatrix(62,194) - factor * groebnerMatrix(13,196); groebnerRow30_010000000_f(groebnerMatrix,62); groebnerRow31_010000000_f(groebnerMatrix,62); groebnerRow32_010000000_f(groebnerMatrix,62); groebnerRow33_010000000_f(groebnerMatrix,62); factor = -groebnerMatrix(62,76); groebnerMatrix(62,76) = 0.0; groebnerMatrix(62,107) = groebnerMatrix(62,107) - factor * groebnerMatrix(18,182); groebnerMatrix(62,142) = groebnerMatrix(62,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(62,77); groebnerMatrix(62,77) = 0.0; groebnerMatrix(62,108) = groebnerMatrix(62,108) - factor * groebnerMatrix(18,182); groebnerMatrix(62,143) = groebnerMatrix(62,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(62,78); groebnerMatrix(62,78) = 0.0; groebnerMatrix(62,113) = groebnerMatrix(62,113) - factor * groebnerMatrix(17,179); groebnerMatrix(62,160) = groebnerMatrix(62,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(62,79); groebnerMatrix(62,79) = 0.0; groebnerMatrix(62,110) = groebnerMatrix(62,110) - factor * groebnerMatrix(18,182); groebnerMatrix(62,148) = groebnerMatrix(62,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(62,80); groebnerMatrix(62,80) = 0.0; groebnerMatrix(62,111) = groebnerMatrix(62,111) - factor * groebnerMatrix(18,182); groebnerMatrix(62,152) = groebnerMatrix(62,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(62,81); groebnerMatrix(62,81) = 0.0; groebnerMatrix(62,116) = groebnerMatrix(62,116) - factor * groebnerMatrix(18,182); groebnerMatrix(62,157) = groebnerMatrix(62,157) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(62,85); groebnerMatrix(62,85) = 0.0; groebnerMatrix(62,93) = groebnerMatrix(62,93) - factor * groebnerMatrix(11,174); groebnerMatrix(62,130) = groebnerMatrix(62,130) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(62,87); groebnerMatrix(62,87) = 0.0; groebnerMatrix(62,122) = groebnerMatrix(62,122) - factor * groebnerMatrix(18,182); groebnerMatrix(62,163) = groebnerMatrix(62,163) - factor * groebnerMatrix(18,187); groebnerRow61_010000000_f(groebnerMatrix,62); groebnerRow41_000000000_f(groebnerMatrix,62); groebnerRow42_000000000_f(groebnerMatrix,62); groebnerRow43_000000000_f(groebnerMatrix,62); factor = -groebnerMatrix(62,94); groebnerMatrix(62,94) = 0.0; groebnerMatrix(62,129) = groebnerMatrix(62,129) - factor * groebnerMatrix(18,182); groebnerMatrix(62,170) = groebnerMatrix(62,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,62); groebnerRow45_000000000_f(groebnerMatrix,62); factor = groebnerMatrix(62,103); groebnerMatrix(62,103) = 0.0; groebnerMatrix(62,108) = groebnerMatrix(62,108) - factor * groebnerMatrix(14,153); groebnerMatrix(62,114) = groebnerMatrix(62,114) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(62,104); groebnerMatrix(62,104) = 0.0; groebnerMatrix(62,107) = groebnerMatrix(62,107) - factor * groebnerMatrix(19,152); groebnerMatrix(62,186) = groebnerMatrix(62,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(62,105); groebnerMatrix(62,105) = 0.0; groebnerMatrix(62,112) = groebnerMatrix(62,112) - factor * groebnerMatrix(28,157); groebnerMatrix(62,185) = groebnerMatrix(62,185) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(62,106); groebnerMatrix(62,106) = 0.0; groebnerMatrix(62,111) = groebnerMatrix(62,111) - factor * groebnerMatrix(13,156); groebnerMatrix(62,117) = groebnerMatrix(62,117) - factor * groebnerMatrix(13,162); groebnerMatrix(62,195) = groebnerMatrix(62,195) - factor * groebnerMatrix(13,196); groebnerRow30_100000000_f(groebnerMatrix,62); groebnerRow31_100000000_f(groebnerMatrix,62); groebnerRow32_100000000_f(groebnerMatrix,62); groebnerRow33_100000000_f(groebnerMatrix,62); groebnerRow34_100000000_f(groebnerMatrix,62); groebnerRow35_100000000_f(groebnerMatrix,62); groebnerRow36_100000000_f(groebnerMatrix,62); groebnerRow37_100000000_f(groebnerMatrix,62); groebnerRow38_100000000_f(groebnerMatrix,62); groebnerRow39_100000000_f(groebnerMatrix,62); factor = groebnerMatrix(62,121); groebnerMatrix(62,121) = 0.0; groebnerMatrix(62,129) = groebnerMatrix(62,129) - factor * groebnerMatrix(11,174); groebnerMatrix(62,138) = groebnerMatrix(62,138) - factor * groebnerMatrix(11,183); factor = -groebnerMatrix(62,122); groebnerMatrix(62,122) = 0.0; groebnerMatrix(62,128) = groebnerMatrix(62,128) - factor * groebnerMatrix(21,173); groebnerMatrix(62,180) = groebnerMatrix(62,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(62,123); groebnerMatrix(62,123) = 0.0; groebnerMatrix(62,136) = groebnerMatrix(62,136) - factor * groebnerMatrix(27,181); groebnerMatrix(62,179) = groebnerMatrix(62,179) - factor * groebnerMatrix(27,188); groebnerRow61_100000000_f(groebnerMatrix,62); groebnerRow47_000000000_f(groebnerMatrix,62); factor = groebnerMatrix(62,127); groebnerMatrix(62,127) = 0.0; groebnerMatrix(62,134) = groebnerMatrix(62,134) - factor * groebnerMatrix(17,179); groebnerMatrix(62,181) = groebnerMatrix(62,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,62); groebnerRow49_000000000_f(groebnerMatrix,62); factor = -groebnerMatrix(62,130); groebnerMatrix(62,130) = 0.0; groebnerMatrix(62,137) = groebnerMatrix(62,137) - factor * groebnerMatrix(18,182); groebnerMatrix(62,178) = groebnerMatrix(62,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,62); groebnerRow51_000000000_f(groebnerMatrix,62); groebnerRow52_000000000_f(groebnerMatrix,62); groebnerRow53_000000000_f(groebnerMatrix,62); groebnerRow54_000000000_f(groebnerMatrix,62); groebnerRow55_000000000_f(groebnerMatrix,62); groebnerRow56_000000000_f(groebnerMatrix,62); groebnerRow57_000000000_f(groebnerMatrix,62); groebnerRow58_000000000_f(groebnerMatrix,62); groebnerRow59_000000000_f(groebnerMatrix,62); groebnerRow60_000000000_f(groebnerMatrix,62); factor = groebnerMatrix(62,142); groebnerMatrix(62,142) = 0.0; groebnerMatrix(62,144) = groebnerMatrix(62,144) - factor * groebnerMatrix(15,144); groebnerMatrix(62,147) = groebnerMatrix(62,147) - factor * groebnerMatrix(15,147); groebnerMatrix(62,196) = groebnerMatrix(62,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(62,143); groebnerMatrix(62,143) = 0.0; groebnerMatrix(62,155) = groebnerMatrix(62,155) - factor * groebnerMatrix(26,155); groebnerMatrix(62,176) = groebnerMatrix(62,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(62,144); groebnerMatrix(62,144) = 0.0; groebnerMatrix(62,156) = groebnerMatrix(62,156) - factor * groebnerMatrix(25,156); groebnerMatrix(62,177) = groebnerMatrix(62,177) - factor * groebnerMatrix(25,177); groebnerMatrix(62,196) = groebnerMatrix(62,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(62,147); groebnerMatrix(62,147) = 0.0; groebnerMatrix(62,162) = groebnerMatrix(62,162) - factor * groebnerMatrix(22,162); groebnerMatrix(62,186) = groebnerMatrix(62,186) - factor * groebnerMatrix(22,186); groebnerMatrix(62,196) = groebnerMatrix(62,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(62,148); groebnerMatrix(62,148) = 0.0; groebnerMatrix(62,153) = groebnerMatrix(62,153) - factor * groebnerMatrix(14,153); groebnerMatrix(62,159) = groebnerMatrix(62,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(62,149); groebnerMatrix(62,149) = 0.0; groebnerMatrix(62,152) = groebnerMatrix(62,152) - factor * groebnerMatrix(19,152); groebnerMatrix(62,195) = groebnerMatrix(62,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(62,150); groebnerMatrix(62,150) = 0.0; groebnerMatrix(62,157) = groebnerMatrix(62,157) - factor * groebnerMatrix(28,157); groebnerMatrix(62,194) = groebnerMatrix(62,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(62,151); groebnerMatrix(62,151) = 0.0; groebnerMatrix(62,156) = groebnerMatrix(62,156) - factor * groebnerMatrix(13,156); groebnerMatrix(62,162) = groebnerMatrix(62,162) - factor * groebnerMatrix(13,162); groebnerMatrix(62,196) = groebnerMatrix(62,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,62); groebnerRow31_000000000_f(groebnerMatrix,62); groebnerRow32_000000000_f(groebnerMatrix,62); groebnerRow33_000000000_f(groebnerMatrix,62); groebnerRow34_000000000_f(groebnerMatrix,62); groebnerRow35_000000000_f(groebnerMatrix,62); groebnerRow36_000000000_f(groebnerMatrix,62); groebnerRow37_000000000_f(groebnerMatrix,62); groebnerRow38_000000000_f(groebnerMatrix,62); groebnerRow39_000000000_f(groebnerMatrix,62); factor = groebnerMatrix(62,163); groebnerMatrix(62,163) = 0.0; groebnerMatrix(62,171) = groebnerMatrix(62,171) - factor * groebnerMatrix(12,171); groebnerMatrix(62,180) = groebnerMatrix(62,180) - factor * groebnerMatrix(12,180); factor = groebnerMatrix(62,166); groebnerMatrix(62,166) = 0.0; groebnerMatrix(62,174) = groebnerMatrix(62,174) - factor * groebnerMatrix(11,174); groebnerMatrix(62,183) = groebnerMatrix(62,183) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(62,168); groebnerMatrix(62,168) = 0.0; groebnerMatrix(62,181) = groebnerMatrix(62,181) - factor * groebnerMatrix(27,181); groebnerMatrix(62,188) = groebnerMatrix(62,188) - factor * groebnerMatrix(27,188); groebnerRow61_000000000_f(groebnerMatrix,62); factor = groebnerMatrix(62,172); groebnerMatrix(62,172) = 0.0; groebnerMatrix(62,179) = groebnerMatrix(62,179) - factor * groebnerMatrix(17,179); groebnerMatrix(62,190) = groebnerMatrix(62,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(62,175); groebnerMatrix(62,175) = 0.0; groebnerMatrix(62,182) = groebnerMatrix(62,182) - factor * groebnerMatrix(18,182); groebnerMatrix(62,187) = groebnerMatrix(62,187) - factor * groebnerMatrix(18,187); sPolynomial63(groebnerMatrix); groebnerRow32_000100000_f(groebnerMatrix,63); groebnerRow33_000100000_f(groebnerMatrix,63); groebnerRow34_000100000_f(groebnerMatrix,63); groebnerRow35_000100000_f(groebnerMatrix,63); groebnerRow36_000100000_f(groebnerMatrix,63); groebnerRow37_000100000_f(groebnerMatrix,63); groebnerRow38_000100000_f(groebnerMatrix,63); groebnerRow39_000100000_f(groebnerMatrix,63); groebnerRow30_010000000_f(groebnerMatrix,63); groebnerRow31_010000000_f(groebnerMatrix,63); groebnerRow32_010000000_f(groebnerMatrix,63); groebnerRow33_010000000_f(groebnerMatrix,63); factor = -groebnerMatrix(63,76); groebnerMatrix(63,76) = 0.0; groebnerMatrix(63,107) = groebnerMatrix(63,107) - factor * groebnerMatrix(18,182); groebnerMatrix(63,142) = groebnerMatrix(63,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(63,77); groebnerMatrix(63,77) = 0.0; groebnerMatrix(63,108) = groebnerMatrix(63,108) - factor * groebnerMatrix(18,182); groebnerMatrix(63,143) = groebnerMatrix(63,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(63,78); groebnerMatrix(63,78) = 0.0; groebnerMatrix(63,113) = groebnerMatrix(63,113) - factor * groebnerMatrix(17,179); groebnerMatrix(63,160) = groebnerMatrix(63,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(63,79); groebnerMatrix(63,79) = 0.0; groebnerMatrix(63,110) = groebnerMatrix(63,110) - factor * groebnerMatrix(18,182); groebnerMatrix(63,148) = groebnerMatrix(63,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(63,80); groebnerMatrix(63,80) = 0.0; groebnerMatrix(63,111) = groebnerMatrix(63,111) - factor * groebnerMatrix(18,182); groebnerMatrix(63,152) = groebnerMatrix(63,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(63,81); groebnerMatrix(63,81) = 0.0; groebnerMatrix(63,116) = groebnerMatrix(63,116) - factor * groebnerMatrix(18,182); groebnerMatrix(63,157) = groebnerMatrix(63,157) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(63,86); groebnerMatrix(63,86) = 0.0; groebnerMatrix(63,92) = groebnerMatrix(63,92) - factor * groebnerMatrix(21,173); groebnerMatrix(63,172) = groebnerMatrix(63,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(63,87); groebnerMatrix(63,87) = 0.0; groebnerMatrix(63,122) = groebnerMatrix(63,122) - factor * groebnerMatrix(18,182); groebnerMatrix(63,163) = groebnerMatrix(63,163) - factor * groebnerMatrix(18,187); groebnerRow61_010000000_f(groebnerMatrix,63); groebnerRow62_010000000_f(groebnerMatrix,63); groebnerRow42_000000000_f(groebnerMatrix,63); groebnerRow43_000000000_f(groebnerMatrix,63); factor = -groebnerMatrix(63,94); groebnerMatrix(63,94) = 0.0; groebnerMatrix(63,129) = groebnerMatrix(63,129) - factor * groebnerMatrix(18,182); groebnerMatrix(63,170) = groebnerMatrix(63,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,63); groebnerRow45_000000000_f(groebnerMatrix,63); groebnerRow30_100000000_f(groebnerMatrix,63); groebnerRow31_100000000_f(groebnerMatrix,63); factor = -groebnerMatrix(63,109); groebnerMatrix(63,109) = 0.0; groebnerMatrix(63,113) = groebnerMatrix(63,113) - factor * groebnerMatrix(16,158); groebnerMatrix(63,184) = groebnerMatrix(63,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,63); groebnerRow33_100000000_f(groebnerMatrix,63); groebnerRow34_100000000_f(groebnerMatrix,63); groebnerRow35_100000000_f(groebnerMatrix,63); groebnerRow36_100000000_f(groebnerMatrix,63); groebnerRow37_100000000_f(groebnerMatrix,63); groebnerRow38_100000000_f(groebnerMatrix,63); groebnerRow39_100000000_f(groebnerMatrix,63); factor = -groebnerMatrix(63,122); groebnerMatrix(63,122) = 0.0; groebnerMatrix(63,128) = groebnerMatrix(63,128) - factor * groebnerMatrix(21,173); groebnerMatrix(63,180) = groebnerMatrix(63,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(63,123); groebnerMatrix(63,123) = 0.0; groebnerMatrix(63,136) = groebnerMatrix(63,136) - factor * groebnerMatrix(27,181); groebnerMatrix(63,179) = groebnerMatrix(63,179) - factor * groebnerMatrix(27,188); groebnerRow61_100000000_f(groebnerMatrix,63); groebnerRow62_100000000_f(groebnerMatrix,63); factor = groebnerMatrix(63,127); groebnerMatrix(63,127) = 0.0; groebnerMatrix(63,134) = groebnerMatrix(63,134) - factor * groebnerMatrix(17,179); groebnerMatrix(63,181) = groebnerMatrix(63,181) - factor * groebnerMatrix(17,190); groebnerRow48_000000000_f(groebnerMatrix,63); groebnerRow49_000000000_f(groebnerMatrix,63); factor = -groebnerMatrix(63,130); groebnerMatrix(63,130) = 0.0; groebnerMatrix(63,137) = groebnerMatrix(63,137) - factor * groebnerMatrix(18,182); groebnerMatrix(63,178) = groebnerMatrix(63,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,63); groebnerRow51_000000000_f(groebnerMatrix,63); groebnerRow52_000000000_f(groebnerMatrix,63); groebnerRow53_000000000_f(groebnerMatrix,63); groebnerRow54_000000000_f(groebnerMatrix,63); groebnerRow55_000000000_f(groebnerMatrix,63); groebnerRow56_000000000_f(groebnerMatrix,63); groebnerRow57_000000000_f(groebnerMatrix,63); groebnerRow58_000000000_f(groebnerMatrix,63); groebnerRow59_000000000_f(groebnerMatrix,63); groebnerRow60_000000000_f(groebnerMatrix,63); factor = groebnerMatrix(63,142); groebnerMatrix(63,142) = 0.0; groebnerMatrix(63,144) = groebnerMatrix(63,144) - factor * groebnerMatrix(15,144); groebnerMatrix(63,147) = groebnerMatrix(63,147) - factor * groebnerMatrix(15,147); groebnerMatrix(63,196) = groebnerMatrix(63,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(63,143); groebnerMatrix(63,143) = 0.0; groebnerMatrix(63,155) = groebnerMatrix(63,155) - factor * groebnerMatrix(26,155); groebnerMatrix(63,176) = groebnerMatrix(63,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(63,144); groebnerMatrix(63,144) = 0.0; groebnerMatrix(63,156) = groebnerMatrix(63,156) - factor * groebnerMatrix(25,156); groebnerMatrix(63,177) = groebnerMatrix(63,177) - factor * groebnerMatrix(25,177); groebnerMatrix(63,196) = groebnerMatrix(63,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(63,147); groebnerMatrix(63,147) = 0.0; groebnerMatrix(63,162) = groebnerMatrix(63,162) - factor * groebnerMatrix(22,162); groebnerMatrix(63,186) = groebnerMatrix(63,186) - factor * groebnerMatrix(22,186); groebnerMatrix(63,196) = groebnerMatrix(63,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(63,148); groebnerMatrix(63,148) = 0.0; groebnerMatrix(63,153) = groebnerMatrix(63,153) - factor * groebnerMatrix(14,153); groebnerMatrix(63,159) = groebnerMatrix(63,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,63); groebnerRow31_000000000_f(groebnerMatrix,63); factor = -groebnerMatrix(63,154); groebnerMatrix(63,154) = 0.0; groebnerMatrix(63,158) = groebnerMatrix(63,158) - factor * groebnerMatrix(16,158); groebnerMatrix(63,193) = groebnerMatrix(63,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,63); groebnerRow33_000000000_f(groebnerMatrix,63); groebnerRow34_000000000_f(groebnerMatrix,63); groebnerRow35_000000000_f(groebnerMatrix,63); groebnerRow36_000000000_f(groebnerMatrix,63); groebnerRow37_000000000_f(groebnerMatrix,63); groebnerRow38_000000000_f(groebnerMatrix,63); groebnerRow39_000000000_f(groebnerMatrix,63); factor = groebnerMatrix(63,163); groebnerMatrix(63,163) = 0.0; groebnerMatrix(63,171) = groebnerMatrix(63,171) - factor * groebnerMatrix(12,171); groebnerMatrix(63,180) = groebnerMatrix(63,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(63,167); groebnerMatrix(63,167) = 0.0; groebnerMatrix(63,173) = groebnerMatrix(63,173) - factor * groebnerMatrix(21,173); groebnerMatrix(63,189) = groebnerMatrix(63,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(63,168); groebnerMatrix(63,168) = 0.0; groebnerMatrix(63,181) = groebnerMatrix(63,181) - factor * groebnerMatrix(27,181); groebnerMatrix(63,188) = groebnerMatrix(63,188) - factor * groebnerMatrix(27,188); groebnerRow61_000000000_f(groebnerMatrix,63); groebnerRow62_000000000_f(groebnerMatrix,63); factor = groebnerMatrix(63,172); groebnerMatrix(63,172) = 0.0; groebnerMatrix(63,179) = groebnerMatrix(63,179) - factor * groebnerMatrix(17,179); groebnerMatrix(63,190) = groebnerMatrix(63,190) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(63,175); groebnerMatrix(63,175) = 0.0; groebnerMatrix(63,182) = groebnerMatrix(63,182) - factor * groebnerMatrix(18,182); groebnerMatrix(63,187) = groebnerMatrix(63,187) - factor * groebnerMatrix(18,187); sPolynomial64(groebnerMatrix); groebnerRow35_000100000_f(groebnerMatrix,64); groebnerRow36_000100000_f(groebnerMatrix,64); groebnerRow37_000100000_f(groebnerMatrix,64); groebnerRow38_000100000_f(groebnerMatrix,64); groebnerRow39_000100000_f(groebnerMatrix,64); factor = groebnerMatrix(64,64); groebnerMatrix(64,64) = 0.0; groebnerMatrix(64,98) = groebnerMatrix(64,98) - factor * groebnerMatrix(17,179); groebnerMatrix(64,148) = groebnerMatrix(64,148) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(64,65); groebnerMatrix(64,65) = 0.0; groebnerMatrix(64,99) = groebnerMatrix(64,99) - factor * groebnerMatrix(17,179); groebnerMatrix(64,149) = groebnerMatrix(64,149) - factor * groebnerMatrix(17,190); factor = groebnerMatrix(64,69); groebnerMatrix(64,69) = 0.0; groebnerMatrix(64,104) = groebnerMatrix(64,104) - factor * groebnerMatrix(17,179); groebnerMatrix(64,151) = groebnerMatrix(64,151) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(64,73); groebnerMatrix(64,73) = 0.0; groebnerMatrix(64,77) = groebnerMatrix(64,77) - factor * groebnerMatrix(16,158); groebnerMatrix(64,176) = groebnerMatrix(64,176) - factor * groebnerMatrix(16,193); factor = -groebnerMatrix(64,76); groebnerMatrix(64,76) = 0.0; groebnerMatrix(64,107) = groebnerMatrix(64,107) - factor * groebnerMatrix(18,182); groebnerMatrix(64,142) = groebnerMatrix(64,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(64,77); groebnerMatrix(64,77) = 0.0; groebnerMatrix(64,108) = groebnerMatrix(64,108) - factor * groebnerMatrix(18,182); groebnerMatrix(64,143) = groebnerMatrix(64,143) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(64,79); groebnerMatrix(64,79) = 0.0; groebnerMatrix(64,110) = groebnerMatrix(64,110) - factor * groebnerMatrix(18,182); groebnerMatrix(64,148) = groebnerMatrix(64,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(64,80); groebnerMatrix(64,80) = 0.0; groebnerMatrix(64,111) = groebnerMatrix(64,111) - factor * groebnerMatrix(18,182); groebnerMatrix(64,152) = groebnerMatrix(64,152) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(64,84); groebnerMatrix(64,84) = 0.0; groebnerMatrix(64,119) = groebnerMatrix(64,119) - factor * groebnerMatrix(17,179); groebnerMatrix(64,166) = groebnerMatrix(64,166) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(64,87); groebnerMatrix(64,87) = 0.0; groebnerMatrix(64,122) = groebnerMatrix(64,122) - factor * groebnerMatrix(18,182); groebnerMatrix(64,163) = groebnerMatrix(64,163) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(64,91); groebnerMatrix(64,91) = 0.0; groebnerMatrix(64,126) = groebnerMatrix(64,126) - factor * groebnerMatrix(17,179); groebnerMatrix(64,173) = groebnerMatrix(64,173) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(64,94); groebnerMatrix(64,94) = 0.0; groebnerMatrix(64,129) = groebnerMatrix(64,129) - factor * groebnerMatrix(18,182); groebnerMatrix(64,170) = groebnerMatrix(64,170) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(64,98); groebnerMatrix(64,98) = 0.0; groebnerMatrix(64,110) = groebnerMatrix(64,110) - factor * groebnerMatrix(26,155); groebnerMatrix(64,131) = groebnerMatrix(64,131) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(64,99); groebnerMatrix(64,99) = 0.0; groebnerMatrix(64,111) = groebnerMatrix(64,111) - factor * groebnerMatrix(25,156); groebnerMatrix(64,132) = groebnerMatrix(64,132) - factor * groebnerMatrix(25,177); groebnerMatrix(64,195) = groebnerMatrix(64,195) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(64,100); groebnerMatrix(64,100) = 0.0; groebnerMatrix(64,115) = groebnerMatrix(64,115) - factor * groebnerMatrix(24,160); groebnerMatrix(64,139) = groebnerMatrix(64,139) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(64,101); groebnerMatrix(64,101) = 0.0; groebnerMatrix(64,116) = groebnerMatrix(64,116) - factor * groebnerMatrix(23,161); groebnerMatrix(64,140) = groebnerMatrix(64,140) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(64,102); groebnerMatrix(64,102) = 0.0; groebnerMatrix(64,117) = groebnerMatrix(64,117) - factor * groebnerMatrix(22,162); groebnerMatrix(64,141) = groebnerMatrix(64,141) - factor * groebnerMatrix(22,186); groebnerMatrix(64,195) = groebnerMatrix(64,195) - factor * groebnerMatrix(22,196); factor = -groebnerMatrix(64,104); groebnerMatrix(64,104) = 0.0; groebnerMatrix(64,107) = groebnerMatrix(64,107) - factor * groebnerMatrix(19,152); groebnerMatrix(64,186) = groebnerMatrix(64,186) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(64,105); groebnerMatrix(64,105) = 0.0; groebnerMatrix(64,112) = groebnerMatrix(64,112) - factor * groebnerMatrix(28,157); groebnerMatrix(64,185) = groebnerMatrix(64,185) - factor * groebnerMatrix(28,194); groebnerRow30_100000000_f(groebnerMatrix,64); groebnerRow31_100000000_f(groebnerMatrix,64); factor = -groebnerMatrix(64,109); groebnerMatrix(64,109) = 0.0; groebnerMatrix(64,113) = groebnerMatrix(64,113) - factor * groebnerMatrix(16,158); groebnerMatrix(64,184) = groebnerMatrix(64,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,64); groebnerRow33_100000000_f(groebnerMatrix,64); groebnerRow34_100000000_f(groebnerMatrix,64); groebnerRow35_100000000_f(groebnerMatrix,64); groebnerRow36_100000000_f(groebnerMatrix,64); groebnerRow37_100000000_f(groebnerMatrix,64); groebnerRow38_100000000_f(groebnerMatrix,64); groebnerRow39_100000000_f(groebnerMatrix,64); factor = groebnerMatrix(64,119); groebnerMatrix(64,119) = 0.0; groebnerMatrix(64,125) = groebnerMatrix(64,125) - factor * groebnerMatrix(20,170); groebnerMatrix(64,183) = groebnerMatrix(64,183) - factor * groebnerMatrix(20,192); factor = -groebnerMatrix(64,120); groebnerMatrix(64,120) = 0.0; groebnerMatrix(64,133) = groebnerMatrix(64,133) - factor * groebnerMatrix(29,178); groebnerMatrix(64,182) = groebnerMatrix(64,182) - factor * groebnerMatrix(29,191); factor = -groebnerMatrix(64,122); groebnerMatrix(64,122) = 0.0; groebnerMatrix(64,128) = groebnerMatrix(64,128) - factor * groebnerMatrix(21,173); groebnerMatrix(64,180) = groebnerMatrix(64,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(64,123); groebnerMatrix(64,123) = 0.0; groebnerMatrix(64,136) = groebnerMatrix(64,136) - factor * groebnerMatrix(27,181); groebnerMatrix(64,179) = groebnerMatrix(64,179) - factor * groebnerMatrix(27,188); groebnerRow61_100000000_f(groebnerMatrix,64); groebnerRow62_100000000_f(groebnerMatrix,64); factor = groebnerMatrix(64,127); groebnerMatrix(64,127) = 0.0; groebnerMatrix(64,134) = groebnerMatrix(64,134) - factor * groebnerMatrix(17,179); groebnerMatrix(64,181) = groebnerMatrix(64,181) - factor * groebnerMatrix(17,190); groebnerRow63_100000000_f(groebnerMatrix,64); groebnerRow49_000000000_f(groebnerMatrix,64); factor = -groebnerMatrix(64,130); groebnerMatrix(64,130) = 0.0; groebnerMatrix(64,137) = groebnerMatrix(64,137) - factor * groebnerMatrix(18,182); groebnerMatrix(64,178) = groebnerMatrix(64,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,64); groebnerRow51_000000000_f(groebnerMatrix,64); groebnerRow52_000000000_f(groebnerMatrix,64); groebnerRow53_000000000_f(groebnerMatrix,64); groebnerRow54_000000000_f(groebnerMatrix,64); groebnerRow55_000000000_f(groebnerMatrix,64); groebnerRow56_000000000_f(groebnerMatrix,64); groebnerRow57_000000000_f(groebnerMatrix,64); groebnerRow58_000000000_f(groebnerMatrix,64); groebnerRow59_000000000_f(groebnerMatrix,64); groebnerRow60_000000000_f(groebnerMatrix,64); factor = groebnerMatrix(64,142); groebnerMatrix(64,142) = 0.0; groebnerMatrix(64,144) = groebnerMatrix(64,144) - factor * groebnerMatrix(15,144); groebnerMatrix(64,147) = groebnerMatrix(64,147) - factor * groebnerMatrix(15,147); groebnerMatrix(64,196) = groebnerMatrix(64,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(64,143); groebnerMatrix(64,143) = 0.0; groebnerMatrix(64,155) = groebnerMatrix(64,155) - factor * groebnerMatrix(26,155); groebnerMatrix(64,176) = groebnerMatrix(64,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(64,144); groebnerMatrix(64,144) = 0.0; groebnerMatrix(64,156) = groebnerMatrix(64,156) - factor * groebnerMatrix(25,156); groebnerMatrix(64,177) = groebnerMatrix(64,177) - factor * groebnerMatrix(25,177); groebnerMatrix(64,196) = groebnerMatrix(64,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(64,145); groebnerMatrix(64,145) = 0.0; groebnerMatrix(64,160) = groebnerMatrix(64,160) - factor * groebnerMatrix(24,160); groebnerMatrix(64,184) = groebnerMatrix(64,184) - factor * groebnerMatrix(24,184); factor = groebnerMatrix(64,146); groebnerMatrix(64,146) = 0.0; groebnerMatrix(64,161) = groebnerMatrix(64,161) - factor * groebnerMatrix(23,161); groebnerMatrix(64,185) = groebnerMatrix(64,185) - factor * groebnerMatrix(23,185); factor = groebnerMatrix(64,147); groebnerMatrix(64,147) = 0.0; groebnerMatrix(64,162) = groebnerMatrix(64,162) - factor * groebnerMatrix(22,162); groebnerMatrix(64,186) = groebnerMatrix(64,186) - factor * groebnerMatrix(22,186); groebnerMatrix(64,196) = groebnerMatrix(64,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(64,148); groebnerMatrix(64,148) = 0.0; groebnerMatrix(64,153) = groebnerMatrix(64,153) - factor * groebnerMatrix(14,153); groebnerMatrix(64,159) = groebnerMatrix(64,159) - factor * groebnerMatrix(14,159); factor = -groebnerMatrix(64,149); groebnerMatrix(64,149) = 0.0; groebnerMatrix(64,152) = groebnerMatrix(64,152) - factor * groebnerMatrix(19,152); groebnerMatrix(64,195) = groebnerMatrix(64,195) - factor * groebnerMatrix(19,195); factor = groebnerMatrix(64,150); groebnerMatrix(64,150) = 0.0; groebnerMatrix(64,157) = groebnerMatrix(64,157) - factor * groebnerMatrix(28,157); groebnerMatrix(64,194) = groebnerMatrix(64,194) - factor * groebnerMatrix(28,194); factor = groebnerMatrix(64,151); groebnerMatrix(64,151) = 0.0; groebnerMatrix(64,156) = groebnerMatrix(64,156) - factor * groebnerMatrix(13,156); groebnerMatrix(64,162) = groebnerMatrix(64,162) - factor * groebnerMatrix(13,162); groebnerMatrix(64,196) = groebnerMatrix(64,196) - factor * groebnerMatrix(13,196); groebnerRow30_000000000_f(groebnerMatrix,64); groebnerRow31_000000000_f(groebnerMatrix,64); factor = -groebnerMatrix(64,154); groebnerMatrix(64,154) = 0.0; groebnerMatrix(64,158) = groebnerMatrix(64,158) - factor * groebnerMatrix(16,158); groebnerMatrix(64,193) = groebnerMatrix(64,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,64); groebnerRow33_000000000_f(groebnerMatrix,64); groebnerRow34_000000000_f(groebnerMatrix,64); groebnerRow35_000000000_f(groebnerMatrix,64); groebnerRow36_000000000_f(groebnerMatrix,64); groebnerRow37_000000000_f(groebnerMatrix,64); groebnerRow38_000000000_f(groebnerMatrix,64); groebnerRow39_000000000_f(groebnerMatrix,64); factor = groebnerMatrix(64,163); groebnerMatrix(64,163) = 0.0; groebnerMatrix(64,171) = groebnerMatrix(64,171) - factor * groebnerMatrix(12,171); groebnerMatrix(64,180) = groebnerMatrix(64,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(64,165); groebnerMatrix(64,165) = 0.0; groebnerMatrix(64,178) = groebnerMatrix(64,178) - factor * groebnerMatrix(29,178); groebnerMatrix(64,191) = groebnerMatrix(64,191) - factor * groebnerMatrix(29,191); factor = groebnerMatrix(64,166); groebnerMatrix(64,166) = 0.0; groebnerMatrix(64,174) = groebnerMatrix(64,174) - factor * groebnerMatrix(11,174); groebnerMatrix(64,183) = groebnerMatrix(64,183) - factor * groebnerMatrix(11,183); factor = groebnerMatrix(64,168); groebnerMatrix(64,168) = 0.0; groebnerMatrix(64,181) = groebnerMatrix(64,181) - factor * groebnerMatrix(27,181); groebnerMatrix(64,188) = groebnerMatrix(64,188) - factor * groebnerMatrix(27,188); groebnerRow61_000000000_f(groebnerMatrix,64); groebnerRow62_000000000_f(groebnerMatrix,64); factor = groebnerMatrix(64,172); groebnerMatrix(64,172) = 0.0; groebnerMatrix(64,179) = groebnerMatrix(64,179) - factor * groebnerMatrix(17,179); groebnerMatrix(64,190) = groebnerMatrix(64,190) - factor * groebnerMatrix(17,190); groebnerRow63_000000000_f(groebnerMatrix,64); factor = -groebnerMatrix(64,175); groebnerMatrix(64,175) = 0.0; groebnerMatrix(64,182) = groebnerMatrix(64,182) - factor * groebnerMatrix(18,182); groebnerMatrix(64,187) = groebnerMatrix(64,187) - factor * groebnerMatrix(18,187); sPolynomial65(groebnerMatrix); factor = -groebnerMatrix(65,30); groebnerMatrix(65,30) = 0.0; groebnerMatrix(65,34) = groebnerMatrix(65,34) - factor * groebnerMatrix(16,158); groebnerMatrix(65,168) = groebnerMatrix(65,168) - factor * groebnerMatrix(16,193); groebnerRow32_000100000_f(groebnerMatrix,65); groebnerRow33_000100000_f(groebnerMatrix,65); groebnerRow34_000100000_f(groebnerMatrix,65); groebnerRow35_000100000_f(groebnerMatrix,65); groebnerRow36_000100000_f(groebnerMatrix,65); groebnerRow37_000100000_f(groebnerMatrix,65); groebnerRow38_000100000_f(groebnerMatrix,65); groebnerRow39_000100000_f(groebnerMatrix,65); groebnerRow30_010000000_f(groebnerMatrix,65); groebnerRow31_010000000_f(groebnerMatrix,65); groebnerRow32_010000000_f(groebnerMatrix,65); groebnerRow33_010000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,76); groebnerMatrix(65,76) = 0.0; groebnerMatrix(65,107) = groebnerMatrix(65,107) - factor * groebnerMatrix(18,182); groebnerMatrix(65,142) = groebnerMatrix(65,142) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(65,77); groebnerMatrix(65,77) = 0.0; groebnerMatrix(65,108) = groebnerMatrix(65,108) - factor * groebnerMatrix(18,182); groebnerMatrix(65,143) = groebnerMatrix(65,143) - factor * groebnerMatrix(18,187); factor = groebnerMatrix(65,78); groebnerMatrix(65,78) = 0.0; groebnerMatrix(65,113) = groebnerMatrix(65,113) - factor * groebnerMatrix(17,179); groebnerMatrix(65,160) = groebnerMatrix(65,160) - factor * groebnerMatrix(17,190); factor = -groebnerMatrix(65,79); groebnerMatrix(65,79) = 0.0; groebnerMatrix(65,110) = groebnerMatrix(65,110) - factor * groebnerMatrix(18,182); groebnerMatrix(65,148) = groebnerMatrix(65,148) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(65,80); groebnerMatrix(65,80) = 0.0; groebnerMatrix(65,111) = groebnerMatrix(65,111) - factor * groebnerMatrix(18,182); groebnerMatrix(65,152) = groebnerMatrix(65,152) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(65,81); groebnerMatrix(65,81) = 0.0; groebnerMatrix(65,116) = groebnerMatrix(65,116) - factor * groebnerMatrix(18,182); groebnerMatrix(65,157) = groebnerMatrix(65,157) - factor * groebnerMatrix(18,187); factor = -groebnerMatrix(65,86); groebnerMatrix(65,86) = 0.0; groebnerMatrix(65,92) = groebnerMatrix(65,92) - factor * groebnerMatrix(21,173); groebnerMatrix(65,172) = groebnerMatrix(65,172) - factor * groebnerMatrix(21,189); factor = -groebnerMatrix(65,87); groebnerMatrix(65,87) = 0.0; groebnerMatrix(65,122) = groebnerMatrix(65,122) - factor * groebnerMatrix(18,182); groebnerMatrix(65,163) = groebnerMatrix(65,163) - factor * groebnerMatrix(18,187); groebnerRow61_010000000_f(groebnerMatrix,65); groebnerRow62_010000000_f(groebnerMatrix,65); groebnerRow63_010000000_f(groebnerMatrix,65); groebnerRow64_010000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,94); groebnerMatrix(65,94) = 0.0; groebnerMatrix(65,129) = groebnerMatrix(65,129) - factor * groebnerMatrix(18,182); groebnerMatrix(65,170) = groebnerMatrix(65,170) - factor * groebnerMatrix(18,187); groebnerRow44_000000000_f(groebnerMatrix,65); groebnerRow45_000000000_f(groebnerMatrix,65); groebnerRow30_100000000_f(groebnerMatrix,65); groebnerRow31_100000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,109); groebnerMatrix(65,109) = 0.0; groebnerMatrix(65,113) = groebnerMatrix(65,113) - factor * groebnerMatrix(16,158); groebnerMatrix(65,184) = groebnerMatrix(65,184) - factor * groebnerMatrix(16,193); groebnerRow32_100000000_f(groebnerMatrix,65); groebnerRow33_100000000_f(groebnerMatrix,65); groebnerRow34_100000000_f(groebnerMatrix,65); groebnerRow35_100000000_f(groebnerMatrix,65); groebnerRow36_100000000_f(groebnerMatrix,65); groebnerRow37_100000000_f(groebnerMatrix,65); groebnerRow38_100000000_f(groebnerMatrix,65); groebnerRow39_100000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,122); groebnerMatrix(65,122) = 0.0; groebnerMatrix(65,128) = groebnerMatrix(65,128) - factor * groebnerMatrix(21,173); groebnerMatrix(65,180) = groebnerMatrix(65,180) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(65,123); groebnerMatrix(65,123) = 0.0; groebnerMatrix(65,136) = groebnerMatrix(65,136) - factor * groebnerMatrix(27,181); groebnerMatrix(65,179) = groebnerMatrix(65,179) - factor * groebnerMatrix(27,188); groebnerRow61_100000000_f(groebnerMatrix,65); groebnerRow62_100000000_f(groebnerMatrix,65); factor = groebnerMatrix(65,127); groebnerMatrix(65,127) = 0.0; groebnerMatrix(65,134) = groebnerMatrix(65,134) - factor * groebnerMatrix(17,179); groebnerMatrix(65,181) = groebnerMatrix(65,181) - factor * groebnerMatrix(17,190); groebnerRow63_100000000_f(groebnerMatrix,65); groebnerRow64_100000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,130); groebnerMatrix(65,130) = 0.0; groebnerMatrix(65,137) = groebnerMatrix(65,137) - factor * groebnerMatrix(18,182); groebnerMatrix(65,178) = groebnerMatrix(65,178) - factor * groebnerMatrix(18,187); groebnerRow50_000000000_f(groebnerMatrix,65); groebnerRow51_000000000_f(groebnerMatrix,65); groebnerRow52_000000000_f(groebnerMatrix,65); groebnerRow53_000000000_f(groebnerMatrix,65); groebnerRow54_000000000_f(groebnerMatrix,65); groebnerRow55_000000000_f(groebnerMatrix,65); groebnerRow56_000000000_f(groebnerMatrix,65); groebnerRow57_000000000_f(groebnerMatrix,65); groebnerRow58_000000000_f(groebnerMatrix,65); groebnerRow59_000000000_f(groebnerMatrix,65); groebnerRow60_000000000_f(groebnerMatrix,65); factor = groebnerMatrix(65,142); groebnerMatrix(65,142) = 0.0; groebnerMatrix(65,144) = groebnerMatrix(65,144) - factor * groebnerMatrix(15,144); groebnerMatrix(65,147) = groebnerMatrix(65,147) - factor * groebnerMatrix(15,147); groebnerMatrix(65,196) = groebnerMatrix(65,196) - factor * groebnerMatrix(15,196); factor = groebnerMatrix(65,143); groebnerMatrix(65,143) = 0.0; groebnerMatrix(65,155) = groebnerMatrix(65,155) - factor * groebnerMatrix(26,155); groebnerMatrix(65,176) = groebnerMatrix(65,176) - factor * groebnerMatrix(26,176); factor = groebnerMatrix(65,144); groebnerMatrix(65,144) = 0.0; groebnerMatrix(65,156) = groebnerMatrix(65,156) - factor * groebnerMatrix(25,156); groebnerMatrix(65,177) = groebnerMatrix(65,177) - factor * groebnerMatrix(25,177); groebnerMatrix(65,196) = groebnerMatrix(65,196) - factor * groebnerMatrix(25,196); factor = groebnerMatrix(65,147); groebnerMatrix(65,147) = 0.0; groebnerMatrix(65,162) = groebnerMatrix(65,162) - factor * groebnerMatrix(22,162); groebnerMatrix(65,186) = groebnerMatrix(65,186) - factor * groebnerMatrix(22,186); groebnerMatrix(65,196) = groebnerMatrix(65,196) - factor * groebnerMatrix(22,196); factor = groebnerMatrix(65,148); groebnerMatrix(65,148) = 0.0; groebnerMatrix(65,153) = groebnerMatrix(65,153) - factor * groebnerMatrix(14,153); groebnerMatrix(65,159) = groebnerMatrix(65,159) - factor * groebnerMatrix(14,159); groebnerRow30_000000000_f(groebnerMatrix,65); groebnerRow31_000000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,154); groebnerMatrix(65,154) = 0.0; groebnerMatrix(65,158) = groebnerMatrix(65,158) - factor * groebnerMatrix(16,158); groebnerMatrix(65,193) = groebnerMatrix(65,193) - factor * groebnerMatrix(16,193); groebnerRow32_000000000_f(groebnerMatrix,65); groebnerRow33_000000000_f(groebnerMatrix,65); groebnerRow34_000000000_f(groebnerMatrix,65); groebnerRow35_000000000_f(groebnerMatrix,65); groebnerRow36_000000000_f(groebnerMatrix,65); groebnerRow37_000000000_f(groebnerMatrix,65); groebnerRow38_000000000_f(groebnerMatrix,65); groebnerRow39_000000000_f(groebnerMatrix,65); factor = groebnerMatrix(65,163); groebnerMatrix(65,163) = 0.0; groebnerMatrix(65,171) = groebnerMatrix(65,171) - factor * groebnerMatrix(12,171); groebnerMatrix(65,180) = groebnerMatrix(65,180) - factor * groebnerMatrix(12,180); factor = -groebnerMatrix(65,167); groebnerMatrix(65,167) = 0.0; groebnerMatrix(65,173) = groebnerMatrix(65,173) - factor * groebnerMatrix(21,173); groebnerMatrix(65,189) = groebnerMatrix(65,189) - factor * groebnerMatrix(21,189); factor = groebnerMatrix(65,168); groebnerMatrix(65,168) = 0.0; groebnerMatrix(65,181) = groebnerMatrix(65,181) - factor * groebnerMatrix(27,181); groebnerMatrix(65,188) = groebnerMatrix(65,188) - factor * groebnerMatrix(27,188); groebnerRow61_000000000_f(groebnerMatrix,65); groebnerRow62_000000000_f(groebnerMatrix,65); factor = groebnerMatrix(65,172); groebnerMatrix(65,172) = 0.0; groebnerMatrix(65,179) = groebnerMatrix(65,179) - factor * groebnerMatrix(17,179); groebnerMatrix(65,190) = groebnerMatrix(65,190) - factor * groebnerMatrix(17,190); groebnerRow63_000000000_f(groebnerMatrix,65); groebnerRow64_000000000_f(groebnerMatrix,65); factor = -groebnerMatrix(65,175); groebnerMatrix(65,175) = 0.0; groebnerMatrix(65,182) = groebnerMatrix(65,182) - factor * groebnerMatrix(18,182); groebnerMatrix(65,187) = groebnerMatrix(65,187) - factor * groebnerMatrix(18,187); factor = 1.0 / groebnerMatrix(10,169); groebnerMatrix.row(10) = factor * groebnerMatrix.row(10); factor = 1.0 / groebnerMatrix(11,166); groebnerMatrix.row(11) = factor * groebnerMatrix.row(11); factor = 1.0 / groebnerMatrix(12,163); groebnerMatrix.row(12) = factor * groebnerMatrix.row(12); factor = 1.0 / groebnerMatrix(13,151); groebnerMatrix.row(13) = factor * groebnerMatrix.row(13); factor = 1.0 / groebnerMatrix(14,148); groebnerMatrix.row(14) = factor * groebnerMatrix.row(14); factor = 1.0 / groebnerMatrix(15,142); groebnerMatrix.row(15) = factor * groebnerMatrix.row(15); factor = 1.0 / groebnerMatrix(16,154); groebnerMatrix.row(16) = factor * groebnerMatrix.row(16); factor = 1.0 / groebnerMatrix(17,172); groebnerMatrix.row(17) = factor * groebnerMatrix.row(17); factor = 1.0 / groebnerMatrix(18,175); groebnerMatrix.row(18) = factor * groebnerMatrix.row(18); factor = 1.0 / groebnerMatrix(19,149); groebnerMatrix.row(19) = factor * groebnerMatrix.row(19); factor = 1.0 / groebnerMatrix(20,164); groebnerMatrix.row(20) = factor * groebnerMatrix.row(20); factor = 1.0 / groebnerMatrix(21,167); groebnerMatrix.row(21) = factor * groebnerMatrix.row(21); factor = 1.0 / groebnerMatrix(22,147); groebnerMatrix.row(22) = factor * groebnerMatrix.row(22); factor = 1.0 / groebnerMatrix(23,146); groebnerMatrix.row(23) = factor * groebnerMatrix.row(23); factor = 1.0 / groebnerMatrix(24,145); groebnerMatrix.row(24) = factor * groebnerMatrix.row(24); factor = 1.0 / groebnerMatrix(25,144); groebnerMatrix.row(25) = factor * groebnerMatrix.row(25); factor = 1.0 / groebnerMatrix(26,143); groebnerMatrix.row(26) = factor * groebnerMatrix.row(26); factor = 1.0 / groebnerMatrix(27,168); groebnerMatrix.row(27) = factor * groebnerMatrix.row(27); factor = 1.0 / groebnerMatrix(28,150); groebnerMatrix.row(28) = factor * groebnerMatrix.row(28); factor = 1.0 / groebnerMatrix(29,165); groebnerMatrix.row(29) = factor * groebnerMatrix.row(29); factor = 1.0 / groebnerMatrix(30,152); groebnerMatrix.row(30) = factor * groebnerMatrix.row(30); factor = 1.0 / groebnerMatrix(31,153); groebnerMatrix.row(31) = factor * groebnerMatrix.row(31); factor = 1.0 / groebnerMatrix(32,155); groebnerMatrix.row(32) = factor * groebnerMatrix.row(32); factor = 1.0 / groebnerMatrix(33,156); groebnerMatrix.row(33) = factor * groebnerMatrix.row(33); factor = 1.0 / groebnerMatrix(34,157); groebnerMatrix.row(34) = factor * groebnerMatrix.row(34); factor = 1.0 / groebnerMatrix(35,158); groebnerMatrix.row(35) = factor * groebnerMatrix.row(35); factor = 1.0 / groebnerMatrix(36,159); groebnerMatrix.row(36) = factor * groebnerMatrix.row(36); factor = 1.0 / groebnerMatrix(37,160); groebnerMatrix.row(37) = factor * groebnerMatrix.row(37); factor = 1.0 / groebnerMatrix(38,161); groebnerMatrix.row(38) = factor * groebnerMatrix.row(38); factor = 1.0 / groebnerMatrix(39,162); groebnerMatrix.row(39) = factor * groebnerMatrix.row(39); factor = 1.0 / groebnerMatrix(45,96); groebnerMatrix.row(45) = factor * groebnerMatrix.row(45); factor = 1.0 / groebnerMatrix(51,132); groebnerMatrix.row(51) = factor * groebnerMatrix.row(51); factor = 1.0 / groebnerMatrix(52,133); groebnerMatrix.row(52) = factor * groebnerMatrix.row(52); factor = 1.0 / groebnerMatrix(53,134); groebnerMatrix.row(53) = factor * groebnerMatrix.row(53); factor = 1.0 / groebnerMatrix(54,135); groebnerMatrix.row(54) = factor * groebnerMatrix.row(54); factor = 1.0 / groebnerMatrix(55,136); groebnerMatrix.row(55) = factor * groebnerMatrix.row(55); factor = 1.0 / groebnerMatrix(56,137); groebnerMatrix.row(56) = factor * groebnerMatrix.row(56); factor = 1.0 / groebnerMatrix(57,138); groebnerMatrix.row(57) = factor * groebnerMatrix.row(57); factor = 1.0 / groebnerMatrix(58,139); groebnerMatrix.row(58) = factor * groebnerMatrix.row(58); factor = 1.0 / groebnerMatrix(59,140); groebnerMatrix.row(59) = factor * groebnerMatrix.row(59); factor = 1.0 / groebnerMatrix(60,141); groebnerMatrix.row(60) = factor * groebnerMatrix.row(60); factor = 1.0 / groebnerMatrix(61,170); groebnerMatrix.row(61) = factor * groebnerMatrix.row(61); factor = 1.0 / groebnerMatrix(62,171); groebnerMatrix.row(62) = factor * groebnerMatrix.row(62); factor = 1.0 / groebnerMatrix(63,173); groebnerMatrix.row(63) = factor * groebnerMatrix.row(63); factor = 1.0 / groebnerMatrix(64,174); groebnerMatrix.row(64) = factor * groebnerMatrix.row(64); factor = 1.0 / groebnerMatrix(65,176); groebnerMatrix.row(65) = factor * groebnerMatrix.row(65); factor = groebnerMatrix(11,174); groebnerMatrix.row(11) = groebnerMatrix.row(11) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(11,176); groebnerMatrix.row(11) = groebnerMatrix.row(11) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(12,171); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(12,173); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(12,174); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(12,176); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(13,156); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(13,157); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(13,158); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(13,159); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(13,160); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(13,161); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(13,162); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(13,170); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(13,171); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(13,173); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(13,174); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(13,176); groebnerMatrix.row(13) = groebnerMatrix.row(13) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(14,153); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(31); factor = groebnerMatrix(14,155); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(14,156); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(14,157); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(14,158); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(14,159); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(14,160); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(14,161); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(14,162); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(14,170); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(14,171); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(14,173); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(14,174); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(14,176); groebnerMatrix.row(14) = groebnerMatrix.row(14) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(15,144); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(25); factor = groebnerMatrix(15,147); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(22); factor = groebnerMatrix(15,156); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(15,157); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(15,158); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(15,159); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(15,160); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(15,161); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(15,162); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(15,170); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(15,171); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(15,173); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(15,174); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(15,176); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(16,158); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(16,159); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(16,160); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(16,161); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(16,162); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(16,170); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(16,171); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(16,173); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(16,174); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(16,176); groebnerMatrix.row(16) = groebnerMatrix.row(16) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(19,152); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(30); factor = groebnerMatrix(19,153); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(31); factor = groebnerMatrix(19,155); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(19,156); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(19,157); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(19,158); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(19,159); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(19,160); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(19,161); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(19,162); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(19,170); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(19,171); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(19,173); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(19,174); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(19,176); groebnerMatrix.row(19) = groebnerMatrix.row(19) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(20,170); groebnerMatrix.row(20) = groebnerMatrix.row(20) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(20,171); groebnerMatrix.row(20) = groebnerMatrix.row(20) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(20,173); groebnerMatrix.row(20) = groebnerMatrix.row(20) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(20,174); groebnerMatrix.row(20) = groebnerMatrix.row(20) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(20,176); groebnerMatrix.row(20) = groebnerMatrix.row(20) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(21,173); groebnerMatrix.row(21) = groebnerMatrix.row(21) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(21,174); groebnerMatrix.row(21) = groebnerMatrix.row(21) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(21,176); groebnerMatrix.row(21) = groebnerMatrix.row(21) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(22,162); groebnerMatrix.row(22) = groebnerMatrix.row(22) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(22,170); groebnerMatrix.row(22) = groebnerMatrix.row(22) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(22,171); groebnerMatrix.row(22) = groebnerMatrix.row(22) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(22,173); groebnerMatrix.row(22) = groebnerMatrix.row(22) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(22,174); groebnerMatrix.row(22) = groebnerMatrix.row(22) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(22,176); groebnerMatrix.row(22) = groebnerMatrix.row(22) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(23,161); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(23,162); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(23,170); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(23,171); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(23,173); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(23,174); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(23,176); groebnerMatrix.row(23) = groebnerMatrix.row(23) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(24,160); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(24,161); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(24,162); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(24,170); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(24,171); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(24,173); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(24,174); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(24,176); groebnerMatrix.row(24) = groebnerMatrix.row(24) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(25,156); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(25,157); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(25,158); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(25,159); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(25,160); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(25,161); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(25,162); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(25,170); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(25,171); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(25,173); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(25,174); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(25,176); groebnerMatrix.row(25) = groebnerMatrix.row(25) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(26,155); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(26,156); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(26,157); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(26,158); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(26,159); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(26,160); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(26,161); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(26,162); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(26,170); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(26,171); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(26,173); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(26,174); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(26,176); groebnerMatrix.row(26) = groebnerMatrix.row(26) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(28,157); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(28,158); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(28,159); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(28,160); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(28,161); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(28,162); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(28,170); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(28,171); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(28,173); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(28,174); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(28,176); groebnerMatrix.row(28) = groebnerMatrix.row(28) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(30,153); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(31); factor = groebnerMatrix(30,155); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(30,156); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(30,157); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(30,158); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(30,159); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(30,160); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(30,161); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(30,162); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(30,170); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(30,171); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(30,173); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(30,174); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(30,176); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(31,155); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(31,156); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(31,157); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(31,158); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(31,159); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(31,160); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(31,161); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(31,162); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(31,170); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(31,171); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(31,173); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(31,174); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(31,176); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(32,156); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(32,157); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(32,158); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(32,159); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(32,160); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(32,161); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(32,162); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(32,170); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(32,171); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(32,173); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(32,174); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(32,176); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(33,157); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(33,158); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(33,159); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(33,160); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(33,161); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(33,162); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(33,170); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(33,171); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(33,173); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(33,174); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(33,176); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(34,158); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(34,159); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(34,160); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(34,161); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(34,162); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(34,170); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(34,171); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(34,173); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(34,174); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(34,176); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(35,159); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(36); factor = groebnerMatrix(35,160); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(35,161); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(35,162); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(35,170); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(35,171); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(35,173); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(35,174); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(35,176); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(36,160); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(36,161); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(36,162); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(36,170); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(36,171); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(36,173); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(36,174); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(36,176); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(37,161); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(37,162); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(37,170); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(37,171); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(37,173); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(37,174); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(37,176); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(38,162); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(38,170); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(38,171); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(38,173); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(38,174); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(38,176); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(39,170); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(39,171); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(39,173); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(39,174); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(39,176); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(45,170); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(45,171); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(45,173); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(45,174); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(45,176); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(45,132); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(51); factor = groebnerMatrix(45,133); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(52); factor = groebnerMatrix(45,134); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(53); factor = groebnerMatrix(45,135); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(54); factor = groebnerMatrix(45,136); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(55); factor = groebnerMatrix(45,137); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(56); factor = groebnerMatrix(45,138); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(45,139); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(45,140); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(45,141); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(45,170); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(45,171); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(45,173); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(45,174); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(45,176); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(51,133); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(52); factor = groebnerMatrix(51,134); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(53); factor = groebnerMatrix(51,135); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(54); factor = groebnerMatrix(51,136); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(55); factor = groebnerMatrix(51,137); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(56); factor = groebnerMatrix(51,138); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(51,139); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(51,140); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(51,141); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(51,170); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(51,171); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(51,173); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(51,174); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(51,176); groebnerMatrix.row(51) = groebnerMatrix.row(51) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(52,134); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(53); factor = groebnerMatrix(52,135); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(54); factor = groebnerMatrix(52,136); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(55); factor = groebnerMatrix(52,137); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(56); factor = groebnerMatrix(52,138); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(52,139); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(52,140); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(52,141); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(52,170); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(52,171); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(52,173); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(52,174); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(52,176); groebnerMatrix.row(52) = groebnerMatrix.row(52) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(53,135); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(54); factor = groebnerMatrix(53,136); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(55); factor = groebnerMatrix(53,137); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(56); factor = groebnerMatrix(53,138); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(53,139); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(53,140); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(53,141); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(53,170); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(53,171); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(53,173); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(53,174); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(53,176); groebnerMatrix.row(53) = groebnerMatrix.row(53) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(54,136); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(55); factor = groebnerMatrix(54,137); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(56); factor = groebnerMatrix(54,138); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(54,139); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(54,140); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(54,141); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(54,170); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(54,171); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(54,173); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(54,174); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(54,176); groebnerMatrix.row(54) = groebnerMatrix.row(54) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(55,137); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(56); factor = groebnerMatrix(55,138); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(55,139); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(55,140); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(55,141); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(55,170); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(55,171); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(55,173); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(55,174); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(55,176); groebnerMatrix.row(55) = groebnerMatrix.row(55) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(56,138); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(57); factor = groebnerMatrix(56,139); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(56,140); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(56,141); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(56,170); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(56,171); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(56,173); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(56,174); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(56,176); groebnerMatrix.row(56) = groebnerMatrix.row(56) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(57,139); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(58); factor = groebnerMatrix(57,140); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(57,141); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(57,170); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(57,171); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(57,173); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(57,174); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(57,176); groebnerMatrix.row(57) = groebnerMatrix.row(57) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(58,140); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(59); factor = groebnerMatrix(58,141); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(58,170); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(58,171); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(58,173); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(58,174); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(58,176); groebnerMatrix.row(58) = groebnerMatrix.row(58) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(59,141); groebnerMatrix.row(59) = groebnerMatrix.row(59) - factor * groebnerMatrix.row(60); factor = groebnerMatrix(59,170); groebnerMatrix.row(59) = groebnerMatrix.row(59) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(59,171); groebnerMatrix.row(59) = groebnerMatrix.row(59) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(59,173); groebnerMatrix.row(59) = groebnerMatrix.row(59) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(59,174); groebnerMatrix.row(59) = groebnerMatrix.row(59) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(59,176); groebnerMatrix.row(59) = groebnerMatrix.row(59) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(60,170); groebnerMatrix.row(60) = groebnerMatrix.row(60) - factor * groebnerMatrix.row(61); factor = groebnerMatrix(60,171); groebnerMatrix.row(60) = groebnerMatrix.row(60) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(60,173); groebnerMatrix.row(60) = groebnerMatrix.row(60) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(60,174); groebnerMatrix.row(60) = groebnerMatrix.row(60) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(60,176); groebnerMatrix.row(60) = groebnerMatrix.row(60) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(61,171); groebnerMatrix.row(61) = groebnerMatrix.row(61) - factor * groebnerMatrix.row(62); factor = groebnerMatrix(61,173); groebnerMatrix.row(61) = groebnerMatrix.row(61) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(61,174); groebnerMatrix.row(61) = groebnerMatrix.row(61) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(61,176); groebnerMatrix.row(61) = groebnerMatrix.row(61) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(62,173); groebnerMatrix.row(62) = groebnerMatrix.row(62) - factor * groebnerMatrix.row(63); factor = groebnerMatrix(62,174); groebnerMatrix.row(62) = groebnerMatrix.row(62) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(62,176); groebnerMatrix.row(62) = groebnerMatrix.row(62) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(63,174); groebnerMatrix.row(63) = groebnerMatrix.row(63) - factor * groebnerMatrix.row(64); factor = groebnerMatrix(63,176); groebnerMatrix.row(63) = groebnerMatrix.row(63) - factor * groebnerMatrix.row(65); factor = groebnerMatrix(64,176); groebnerMatrix.row(64) = groebnerMatrix.row(64) - factor * groebnerMatrix.row(65); } opengv/src/relative_pose/modules/ge/0000775016516101651610000000000013344612246016502 5ustar dimadimaopengv/src/relative_pose/modules/ge/modules.cpp0000664016516101651610000014267613344612246020676 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include void opengv::relative_pose::modules::ge::getEV( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, Eigen::Vector4d & roots ) { Eigen::Matrix4d G = composeG(xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley); // now compute the roots in closed-form //double G00_2 = G(0,0) * G(0,0); double G01_2 = G(0,1) * G(0,1); double G02_2 = G(0,2) * G(0,2); double G03_2 = G(0,3) * G(0,3); //double G11_2 = G(1,1) * G(1,1); double G12_2 = G(1,2) * G(1,2); double G13_2 = G(1,3) * G(1,3); //double G22_2 = G(2,2) * G(2,2); double G23_2 = G(2,3) * G(2,3); //double G33_2 = G(3,3) * G(3,3); double B = -G(3,3)-G(2,2)-G(1,1)-G(0,0); double C = -G23_2+G(2,2)*G(3,3)-G13_2-G12_2+G(1,1)*G(3,3)+G(1,1)*G(2,2)-G03_2-G02_2-G01_2+G(0,0)*G(3,3)+G(0,0)*G(2,2)+G(0,0)*G(1,1); double D = G13_2*G(2,2)-2.0*G(1,2)*G(1,3)*G(2,3)+G12_2*G(3,3)+G(1,1)*G23_2-G(1,1)*G(2,2)*G(3,3)+G03_2*G(2,2)+G03_2*G(1,1)-2.0*G(0,2)*G(0,3)*G(2,3)+G02_2*G(3,3)+G02_2*G(1,1)-2.0*G(0,1)*G(0,3)*G(1,3)-2.0*G(0,1)*G(0,2)*G(1,2)+G01_2*G(3,3)+G01_2*G(2,2)+G(0,0)*G23_2-G(0,0)*G(2,2)*G(3,3)+G(0,0)*G13_2+G(0,0)*G12_2-G(0,0)*G(1,1)*G(3,3)-G(0,0)*G(1,1)*G(2,2); double E = G03_2*G12_2-G03_2*G(1,1)*G(2,2)-2.0*G(0,2)*G(0,3)*G(1,2)*G(1,3)+2.0*G(0,2)*G(0,3)*G(1,1)*G(2,3)+G02_2*G13_2-G02_2*G(1,1)*G(3,3)+2.0*G(0,1)*G(0,3)*G(1,3)*G(2,2)-2.0*G(0,1)*G(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G(0,2)*G(1,3)*G(2,3)+2.0*G(0,1)*G(0,2)*G(1,2)*G(3,3)+G01_2*G23_2-G01_2*G(2,2)*G(3,3)-G(0,0)*G13_2*G(2,2)+2.0*G(0,0)*G(1,2)*G(1,3)*G(2,3)-G(0,0)*G12_2*G(3,3)-G(0,0)*G(1,1)*G23_2+G(0,0)*G(1,1)*G(2,2)*G(3,3); double B_pw2 = B*B; double B_pw3 = B_pw2*B; double B_pw4 = B_pw3*B; double alpha = -0.375*B_pw2+C; double beta = B_pw3/8.0-B*C/2.0+D; double gamma = -0.01171875*B_pw4+B_pw2*C/16.0-B*D/4.0+E; double alpha_pw2 = alpha*alpha; double alpha_pw3 = alpha_pw2*alpha; double p = -alpha_pw2/12.0-gamma; double q = -alpha_pw3/108.0+alpha*gamma/3.0-pow(beta,2.0)/8.0; double helper1 = -pow(p,3.0)/27.0; double theta2 = pow( helper1, (1.0/3.0) ); double theta1 = sqrt(theta2) * cos( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ); double y = -(5.0/6.0)*alpha - ( (1.0/3.0) * p * theta1 - theta1 * theta2) / theta2; double w = sqrt(alpha+2.0*y); //we currently disable the computation of all other roots, they are not used //roots[0] = -B/4.0 + 0.5*w + 0.5*sqrt(-3.0*alpha-2.0*y-2.0*beta/w); //roots[1] = -B/4.0 + 0.5*w - 0.5*sqrt(-3.0*alpha-2.0*y-2.0*beta/w); double temp1 = -B/4.0 - 0.5*w; double temp2 = 0.5*sqrt(-3.0*alpha-2.0*y+2.0*beta/w); //roots[2] = -B/4.0 - 0.5*w + 0.5*sqrt(-3.0*alpha-2.0*y+2.0*beta/w); //roots[3] = -B/4.0 - 0.5*w - 0.5*sqrt(-3.0*alpha-2.0*y+2.0*beta/w); //this is the smallest one! roots[2] = temp1 + temp2; roots[3] = temp1 - temp2; } double opengv::relative_pose::modules::ge::getCost( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, int step ) { Eigen::Vector4d roots; getEV(xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,roots); double cost = 0.0; if( step == 0 ) cost = roots[2]; if( step == 1 ) cost = roots[3]; return cost; } /////////////////////////// Code for analytical computation of jacobian (for smallest root) /////////////////////// /* Eigen::Matrix4d G_jac1 = Eigen::Matrix4d::Zero(); Eigen::Matrix4d G_jac2 = Eigen::Matrix4d::Zero(); Eigen::Matrix4d G_jac3 = Eigen::Matrix4d::Zero(); Eigen::Matrix4d G = composeGwithJacobians( xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,G_jac1,G_jac2,G_jac3); double B = -G(3,3)-G(2,2)-G(1,1)-G(0,0); double B_jac1 = -G_jac1(3,3)-G_jac1(2,2)-G_jac1(1,1)-G_jac1(0,0); double B_jac2 = -G_jac2(3,3)-G_jac2(2,2)-G_jac2(1,1)-G_jac2(0,0); double B_jac3 = -G_jac3(3,3)-G_jac3(2,2)-G_jac3(1,1)-G_jac3(0,0); double C = -pow(G(2,3),2)+G(2,2)*G(3,3)-pow(G(1,3),2)-pow(G(1,2),2)+G(1,1)*G(3,3)+G(1,1)*G(2,2)-pow(G(0,3),2)-pow(G(0,2),2)-pow(G(0,1),2)+G(0,0)*G(3,3)+G(0,0)*G(2,2)+G(0,0)*G(1,1); double C_jac1 = -2.0*G(2,3)*G_jac1(2,3)+G_jac1(2,2)*G(3,3)+G(2,2)*G_jac1(3,3)-2.0*G(1,3)*G_jac1(1,3)-2.0*G(1,2)*G_jac1(1,2)+G_jac1(1,1)*G(3,3)+G(1,1)*G_jac1(3,3)+G_jac1(1,1)*G(2,2)+G(1,1)*G_jac1(2,2)-2.0*G(0,3)*G_jac1(0,3)-2.0*G(0,2)*G_jac1(0,2)-2.0*G(0,1)*G_jac1(0,1)+G_jac1(0,0)*G(3,3)+G(0,0)*G_jac1(3,3)+G_jac1(0,0)*G(2,2)+G(0,0)*G_jac1(2,2)+G_jac1(0,0)*G(1,1)+G(0,0)*G_jac1(1,1); double C_jac2 = -2.0*G(2,3)*G_jac2(2,3)+G_jac2(2,2)*G(3,3)+G(2,2)*G_jac2(3,3)-2.0*G(1,3)*G_jac2(1,3)-2.0*G(1,2)*G_jac2(1,2)+G_jac2(1,1)*G(3,3)+G(1,1)*G_jac2(3,3)+G_jac2(1,1)*G(2,2)+G(1,1)*G_jac2(2,2)-2.0*G(0,3)*G_jac2(0,3)-2.0*G(0,2)*G_jac2(0,2)-2.0*G(0,1)*G_jac2(0,1)+G_jac2(0,0)*G(3,3)+G(0,0)*G_jac2(3,3)+G_jac2(0,0)*G(2,2)+G(0,0)*G_jac2(2,2)+G_jac2(0,0)*G(1,1)+G(0,0)*G_jac2(1,1); double C_jac3 = -2.0*G(2,3)*G_jac3(2,3)+G_jac3(2,2)*G(3,3)+G(2,2)*G_jac3(3,3)-2.0*G(1,3)*G_jac3(1,3)-2.0*G(1,2)*G_jac3(1,2)+G_jac3(1,1)*G(3,3)+G(1,1)*G_jac3(3,3)+G_jac3(1,1)*G(2,2)+G(1,1)*G_jac3(2,2)-2.0*G(0,3)*G_jac3(0,3)-2.0*G(0,2)*G_jac3(0,2)-2.0*G(0,1)*G_jac3(0,1)+G_jac3(0,0)*G(3,3)+G(0,0)*G_jac3(3,3)+G_jac3(0,0)*G(2,2)+G(0,0)*G_jac3(2,2)+G_jac3(0,0)*G(1,1)+G(0,0)*G_jac3(1,1); double D = pow(G(1,3),2)*G(2,2)-2.0*G(1,2)*G(1,3)*G(2,3)+pow(G(1,2),2)*G(3,3)+G(1,1)*pow(G(2,3),2)-G(1,1)*G(2,2)*G(3,3)+pow(G(0,3),2)*G(2,2)+pow(G(0,3),2)*G(1,1)-2.0*G(0,2)*G(0,3)*G(2,3)+pow(G(0,2),2)*G(3,3)+pow(G(0,2),2)*G(1,1)-2.0*G(0,1)*G(0,3)*G(1,3)-2.0*G(0,1)*G(0,2)*G(1,2)+pow(G(0,1),2)*G(3,3)+pow(G(0,1),2)*G(2,2)+G(0,0)*pow(G(2,3),2)-G(0,0)*G(2,2)*G(3,3)+G(0,0)*pow(G(1,3),2)+G(0,0)*pow(G(1,2),2)-G(0,0)*G(1,1)*G(3,3)-G(0,0)*G(1,1)*G(2,2); double D_jac1 = 2.0*G(1,3)*G_jac1(1,3)*G(2,2)+pow(G(1,3),2)*G_jac1(2,2)-2.0*G_jac1(1,2)*G(1,3)*G(2,3)-2.0*G(1,2)*G_jac1(1,3)*G(2,3)-2.0*G(1,2)*G(1,3)*G_jac1(2,3)+2.0*G(1,2)*G_jac1(1,2)*G(3,3)+pow(G(1,2),2)*G_jac1(3,3)+G_jac1(1,1)*pow(G(2,3),2)+G(1,1)*2.0*G(2,3)*G_jac1(2,3)-G_jac1(1,1)*G(2,2)*G(3,3)-G(1,1)*G_jac1(2,2)*G(3,3)-G(1,1)*G(2,2)*G_jac1(3,3)+2.0*G(0,3)*G_jac1(0,3)*G(2,2)+pow(G(0,3),2)*G_jac1(2,2)+2.0*G(0,3)*G_jac1(0,3)*G(1,1)+pow(G(0,3),2)*G_jac1(1,1)-2.0*G_jac1(0,2)*G(0,3)*G(2,3)-2.0*G(0,2)*G_jac1(0,3)*G(2,3)-2.0*G(0,2)*G(0,3)*G_jac1(2,3)+2.0*G(0,2)*G_jac1(0,2)*G(3,3)+pow(G(0,2),2)*G_jac1(3,3)+2.0*G(0,2)*G_jac1(0,2)*G(1,1)+pow(G(0,2),2)*G_jac1(1,1)-2.0*G_jac1(0,1)*G(0,3)*G(1,3)-2.0*G(0,1)*G_jac1(0,3)*G(1,3)-2.0*G(0,1)*G(0,3)*G_jac1(1,3)-2.0*G_jac1(0,1)*G(0,2)*G(1,2)-2.0*G(0,1)*G_jac1(0,2)*G(1,2)-2.0*G(0,1)*G(0,2)*G_jac1(1,2)+2.0*G(0,1)*G_jac1(0,1)*G(3,3)+pow(G(0,1),2)*G_jac1(3,3)+2.0*G(0,1)*G_jac1(0,1)*G(2,2)+pow(G(0,1),2)*G_jac1(2,2)+G_jac1(0,0)*pow(G(2,3),2)+G(0,0)*2.0*G(2,3)*G_jac1(2,3)-G_jac1(0,0)*G(2,2)*G(3,3)-G(0,0)*G_jac1(2,2)*G(3,3)-G(0,0)*G(2,2)*G_jac1(3,3)+G_jac1(0,0)*pow(G(1,3),2)+G(0,0)*2.0*G(1,3)*G_jac1(1,3)+G_jac1(0,0)*pow(G(1,2),2)+G(0,0)*2.0*G(1,2)*G_jac1(1,2)-G_jac1(0,0)*G(1,1)*G(3,3)-G(0,0)*G_jac1(1,1)*G(3,3)-G(0,0)*G(1,1)*G_jac1(3,3)-G_jac1(0,0)*G(1,1)*G(2,2)-G(0,0)*G_jac1(1,1)*G(2,2)-G(0,0)*G(1,1)*G_jac1(2,2); double D_jac2 = 2.0*G(1,3)*G_jac2(1,3)*G(2,2)+pow(G(1,3),2)*G_jac2(2,2)-2.0*G_jac2(1,2)*G(1,3)*G(2,3)-2.0*G(1,2)*G_jac2(1,3)*G(2,3)-2.0*G(1,2)*G(1,3)*G_jac2(2,3)+2.0*G(1,2)*G_jac2(1,2)*G(3,3)+pow(G(1,2),2)*G_jac2(3,3)+G_jac2(1,1)*pow(G(2,3),2)+G(1,1)*2.0*G(2,3)*G_jac2(2,3)-G_jac2(1,1)*G(2,2)*G(3,3)-G(1,1)*G_jac2(2,2)*G(3,3)-G(1,1)*G(2,2)*G_jac2(3,3)+2.0*G(0,3)*G_jac2(0,3)*G(2,2)+pow(G(0,3),2)*G_jac2(2,2)+2.0*G(0,3)*G_jac2(0,3)*G(1,1)+pow(G(0,3),2)*G_jac2(1,1)-2.0*G_jac2(0,2)*G(0,3)*G(2,3)-2.0*G(0,2)*G_jac2(0,3)*G(2,3)-2.0*G(0,2)*G(0,3)*G_jac2(2,3)+2.0*G(0,2)*G_jac2(0,2)*G(3,3)+pow(G(0,2),2)*G_jac2(3,3)+2.0*G(0,2)*G_jac2(0,2)*G(1,1)+pow(G(0,2),2)*G_jac2(1,1)-2.0*G_jac2(0,1)*G(0,3)*G(1,3)-2.0*G(0,1)*G_jac2(0,3)*G(1,3)-2.0*G(0,1)*G(0,3)*G_jac2(1,3)-2.0*G_jac2(0,1)*G(0,2)*G(1,2)-2.0*G(0,1)*G_jac2(0,2)*G(1,2)-2.0*G(0,1)*G(0,2)*G_jac2(1,2)+2.0*G(0,1)*G_jac2(0,1)*G(3,3)+pow(G(0,1),2)*G_jac2(3,3)+2.0*G(0,1)*G_jac2(0,1)*G(2,2)+pow(G(0,1),2)*G_jac2(2,2)+G_jac2(0,0)*pow(G(2,3),2)+G(0,0)*2.0*G(2,3)*G_jac2(2,3)-G_jac2(0,0)*G(2,2)*G(3,3)-G(0,0)*G_jac2(2,2)*G(3,3)-G(0,0)*G(2,2)*G_jac2(3,3)+G_jac2(0,0)*pow(G(1,3),2)+G(0,0)*2.0*G(1,3)*G_jac2(1,3)+G_jac2(0,0)*pow(G(1,2),2)+G(0,0)*2.0*G(1,2)*G_jac2(1,2)-G_jac2(0,0)*G(1,1)*G(3,3)-G(0,0)*G_jac2(1,1)*G(3,3)-G(0,0)*G(1,1)*G_jac2(3,3)-G_jac2(0,0)*G(1,1)*G(2,2)-G(0,0)*G_jac2(1,1)*G(2,2)-G(0,0)*G(1,1)*G_jac2(2,2); double D_jac3 = 2.0*G(1,3)*G_jac3(1,3)*G(2,2)+pow(G(1,3),2)*G_jac3(2,2)-2.0*G_jac3(1,2)*G(1,3)*G(2,3)-2.0*G(1,2)*G_jac3(1,3)*G(2,3)-2.0*G(1,2)*G(1,3)*G_jac3(2,3)+2.0*G(1,2)*G_jac3(1,2)*G(3,3)+pow(G(1,2),2)*G_jac3(3,3)+G_jac3(1,1)*pow(G(2,3),2)+G(1,1)*2.0*G(2,3)*G_jac3(2,3)-G_jac3(1,1)*G(2,2)*G(3,3)-G(1,1)*G_jac3(2,2)*G(3,3)-G(1,1)*G(2,2)*G_jac3(3,3)+2.0*G(0,3)*G_jac3(0,3)*G(2,2)+pow(G(0,3),2)*G_jac3(2,2)+2.0*G(0,3)*G_jac3(0,3)*G(1,1)+pow(G(0,3),2)*G_jac3(1,1)-2.0*G_jac3(0,2)*G(0,3)*G(2,3)-2.0*G(0,2)*G_jac3(0,3)*G(2,3)-2.0*G(0,2)*G(0,3)*G_jac3(2,3)+2.0*G(0,2)*G_jac3(0,2)*G(3,3)+pow(G(0,2),2)*G_jac3(3,3)+2.0*G(0,2)*G_jac3(0,2)*G(1,1)+pow(G(0,2),2)*G_jac3(1,1)-2.0*G_jac3(0,1)*G(0,3)*G(1,3)-2.0*G(0,1)*G_jac3(0,3)*G(1,3)-2.0*G(0,1)*G(0,3)*G_jac3(1,3)-2.0*G_jac3(0,1)*G(0,2)*G(1,2)-2.0*G(0,1)*G_jac3(0,2)*G(1,2)-2.0*G(0,1)*G(0,2)*G_jac3(1,2)+2.0*G(0,1)*G_jac3(0,1)*G(3,3)+pow(G(0,1),2)*G_jac3(3,3)+2.0*G(0,1)*G_jac3(0,1)*G(2,2)+pow(G(0,1),2)*G_jac3(2,2)+G_jac3(0,0)*pow(G(2,3),2)+G(0,0)*2.0*G(2,3)*G_jac3(2,3)-G_jac3(0,0)*G(2,2)*G(3,3)-G(0,0)*G_jac3(2,2)*G(3,3)-G(0,0)*G(2,2)*G_jac3(3,3)+G_jac3(0,0)*pow(G(1,3),2)+G(0,0)*2.0*G(1,3)*G_jac3(1,3)+G_jac3(0,0)*pow(G(1,2),2)+G(0,0)*2.0*G(1,2)*G_jac3(1,2)-G_jac3(0,0)*G(1,1)*G(3,3)-G(0,0)*G_jac3(1,1)*G(3,3)-G(0,0)*G(1,1)*G_jac3(3,3)-G_jac3(0,0)*G(1,1)*G(2,2)-G(0,0)*G_jac3(1,1)*G(2,2)-G(0,0)*G(1,1)*G_jac3(2,2); double E = pow(G(0,3),2)*pow(G(1,2),2)-pow(G(0,3),2)*G(1,1)*G(2,2)-2.0*G(0,2)*G(0,3)*G(1,2)*G(1,3)+2.0*G(0,2)*G(0,3)*G(1,1)*G(2,3)+pow(G(0,2),2)*pow(G(1,3),2)-pow(G(0,2),2)*G(1,1)*G(3,3)+2.0*G(0,1)*G(0,3)*G(1,3)*G(2,2)-2.0*G(0,1)*G(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G(0,2)*G(1,3)*G(2,3)+2.0*G(0,1)*G(0,2)*G(1,2)*G(3,3)+pow(G(0,1),2)*pow(G(2,3),2)-pow(G(0,1),2)*G(2,2)*G(3,3)-G(0,0)*pow(G(1,3),2)*G(2,2)+2.0*G(0,0)*G(1,2)*G(1,3)*G(2,3)-G(0,0)*pow(G(1,2),2)*G(3,3)-G(0,0)*G(1,1)*pow(G(2,3),2)+G(0,0)*G(1,1)*G(2,2)*G(3,3); double E_jac1 = 2.0*G(0,3)*G_jac1(0,3)*pow(G(1,2),2)+pow(G(0,3),2)*2.0*G(1,2)*G_jac1(1,2)-2.0*G(0,3)*G_jac1(0,3)*G(1,1)*G(2,2)-pow(G(0,3),2)*G_jac1(1,1)*G(2,2)-pow(G(0,3),2)*G(1,1)*G_jac1(2,2)-2.0*G_jac1(0,2)*G(0,3)*G(1,2)*G(1,3)-2.0*G(0,2)*G_jac1(0,3)*G(1,2)*G(1,3)-2.0*G(0,2)*G(0,3)*G_jac1(1,2)*G(1,3)-2.0*G(0,2)*G(0,3)*G(1,2)*G_jac1(1,3)+2.0*G_jac1(0,2)*G(0,3)*G(1,1)*G(2,3)+2.0*G(0,2)*G_jac1(0,3)*G(1,1)*G(2,3)+2.0*G(0,2)*G(0,3)*G_jac1(1,1)*G(2,3)+2.0*G(0,2)*G(0,3)*G(1,1)*G_jac1(2,3) +2.0*G(0,2)*G_jac1(0,2)*pow(G(1,3),2)+pow(G(0,2),2)*2.0*G(1,3)*G_jac1(1,3)-2.0*G(0,2)*G_jac1(0,2)*G(1,1)*G(3,3)-pow(G(0,2),2)*G_jac1(1,1)*G(3,3)-pow(G(0,2),2)*G(1,1)*G_jac1(3,3)+2.0*G_jac1(0,1)*G(0,3)*G(1,3)*G(2,2)+2.0*G(0,1)*G_jac1(0,3)*G(1,3)*G(2,2)+2.0*G(0,1)*G(0,3)*G_jac1(1,3)*G(2,2)+2.0*G(0,1)*G(0,3)*G(1,3)*G_jac1(2,2)-2.0*G_jac1(0,1)*G(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G_jac1(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G(0,3)*G_jac1(1,2)*G(2,3)-2.0*G(0,1)*G(0,3)*G(1,2)*G_jac1(2,3)-2.0*G_jac1(0,1)*G(0,2)*G(1,3)*G(2,3)-2.0*G(0,1)*G_jac1(0,2)*G(1,3)*G(2,3)-2.0*G(0,1)*G(0,2)*G_jac1(1,3)*G(2,3)-2.0*G(0,1)*G(0,2)*G(1,3)*G_jac1(2,3)+2.0*G_jac1(0,1)*G(0,2)*G(1,2)*G(3,3)+2.0*G(0,1)*G_jac1(0,2)*G(1,2)*G(3,3)+2.0*G(0,1)*G(0,2)*G_jac1(1,2)*G(3,3)+2.0*G(0,1)*G(0,2)*G(1,2)*G_jac1(3,3)+2.0*G(0,1)*G_jac1(0,1)*pow(G(2,3),2)+pow(G(0,1),2)*2.0*G(2,3)*G_jac1(2,3)-2.0*G(0,1)*G_jac1(0,1)*G(2,2)*G(3,3)-pow(G(0,1),2)*G_jac1(2,2)*G(3,3)-pow(G(0,1),2)*G(2,2)*G_jac1(3,3)-G_jac1(0,0)*pow(G(1,3),2)*G(2,2)-G(0,0)*2.0*G(1,3)*G_jac1(1,3)*G(2,2)-G(0,0)*pow(G(1,3),2)*G_jac1(2,2)+2.0*G_jac1(0,0)*G(1,2)*G(1,3)*G(2,3)+2.0*G(0,0)*G_jac1(1,2)*G(1,3)*G(2,3)+2.0*G(0,0)*G(1,2)*G_jac1(1,3)*G(2,3)+2.0*G(0,0)*G(1,2)*G(1,3)*G_jac1(2,3)-G_jac1(0,0)*pow(G(1,2),2)*G(3,3)-G(0,0)*2.0*G(1,2)*G_jac1(1,2)*G(3,3)-G(0,0)*pow(G(1,2),2)*G_jac1(3,3)-G_jac1(0,0)*G(1,1)*pow(G(2,3),2)-G(0,0)*G_jac1(1,1)*pow(G(2,3),2)-G(0,0)*G(1,1)*2.0*G(2,3)*G_jac1(2,3)+G_jac1(0,0)*G(1,1)*G(2,2)*G(3,3)+G(0,0)*G_jac1(1,1)*G(2,2)*G(3,3)+G(0,0)*G(1,1)*G_jac1(2,2)*G(3,3)+G(0,0)*G(1,1)*G(2,2)*G_jac1(3,3); double E_jac2 = 2.0*G(0,3)*G_jac2(0,3)*pow(G(1,2),2)+pow(G(0,3),2)*2.0*G(1,2)*G_jac2(1,2)-2.0*G(0,3)*G_jac2(0,3)*G(1,1)*G(2,2)-pow(G(0,3),2)*G_jac2(1,1)*G(2,2)-pow(G(0,3),2)*G(1,1)*G_jac2(2,2)-2.0*G_jac2(0,2)*G(0,3)*G(1,2)*G(1,3)-2.0*G(0,2)*G_jac2(0,3)*G(1,2)*G(1,3)-2.0*G(0,2)*G(0,3)*G_jac2(1,2)*G(1,3)-2.0*G(0,2)*G(0,3)*G(1,2)*G_jac2(1,3)+2.0*G_jac2(0,2)*G(0,3)*G(1,1)*G(2,3)+2.0*G(0,2)*G_jac2(0,3)*G(1,1)*G(2,3)+2.0*G(0,2)*G(0,3)*G_jac2(1,1)*G(2,3)+2.0*G(0,2)*G(0,3)*G(1,1)*G_jac2(2,3) +2.0*G(0,2)*G_jac2(0,2)*pow(G(1,3),2)+pow(G(0,2),2)*2.0*G(1,3)*G_jac2(1,3)-2.0*G(0,2)*G_jac2(0,2)*G(1,1)*G(3,3)-pow(G(0,2),2)*G_jac2(1,1)*G(3,3)-pow(G(0,2),2)*G(1,1)*G_jac2(3,3)+2.0*G_jac2(0,1)*G(0,3)*G(1,3)*G(2,2)+2.0*G(0,1)*G_jac2(0,3)*G(1,3)*G(2,2)+2.0*G(0,1)*G(0,3)*G_jac2(1,3)*G(2,2)+2.0*G(0,1)*G(0,3)*G(1,3)*G_jac2(2,2)-2.0*G_jac2(0,1)*G(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G_jac2(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G(0,3)*G_jac2(1,2)*G(2,3)-2.0*G(0,1)*G(0,3)*G(1,2)*G_jac2(2,3)-2.0*G_jac2(0,1)*G(0,2)*G(1,3)*G(2,3)-2.0*G(0,1)*G_jac2(0,2)*G(1,3)*G(2,3)-2.0*G(0,1)*G(0,2)*G_jac2(1,3)*G(2,3)-2.0*G(0,1)*G(0,2)*G(1,3)*G_jac2(2,3)+2.0*G_jac2(0,1)*G(0,2)*G(1,2)*G(3,3)+2.0*G(0,1)*G_jac2(0,2)*G(1,2)*G(3,3)+2.0*G(0,1)*G(0,2)*G_jac2(1,2)*G(3,3)+2.0*G(0,1)*G(0,2)*G(1,2)*G_jac2(3,3)+2.0*G(0,1)*G_jac2(0,1)*pow(G(2,3),2)+pow(G(0,1),2)*2.0*G(2,3)*G_jac2(2,3)-2.0*G(0,1)*G_jac2(0,1)*G(2,2)*G(3,3)-pow(G(0,1),2)*G_jac2(2,2)*G(3,3)-pow(G(0,1),2)*G(2,2)*G_jac2(3,3)-G_jac2(0,0)*pow(G(1,3),2)*G(2,2)-G(0,0)*2.0*G(1,3)*G_jac2(1,3)*G(2,2)-G(0,0)*pow(G(1,3),2)*G_jac2(2,2)+2.0*G_jac2(0,0)*G(1,2)*G(1,3)*G(2,3)+2.0*G(0,0)*G_jac2(1,2)*G(1,3)*G(2,3)+2.0*G(0,0)*G(1,2)*G_jac2(1,3)*G(2,3)+2.0*G(0,0)*G(1,2)*G(1,3)*G_jac2(2,3)-G_jac2(0,0)*pow(G(1,2),2)*G(3,3)-G(0,0)*2.0*G(1,2)*G_jac2(1,2)*G(3,3)-G(0,0)*pow(G(1,2),2)*G_jac2(3,3)-G_jac2(0,0)*G(1,1)*pow(G(2,3),2)-G(0,0)*G_jac2(1,1)*pow(G(2,3),2)-G(0,0)*G(1,1)*2.0*G(2,3)*G_jac2(2,3)+G_jac2(0,0)*G(1,1)*G(2,2)*G(3,3)+G(0,0)*G_jac2(1,1)*G(2,2)*G(3,3)+G(0,0)*G(1,1)*G_jac2(2,2)*G(3,3)+G(0,0)*G(1,1)*G(2,2)*G_jac2(3,3); double E_jac3 = 2.0*G(0,3)*G_jac3(0,3)*pow(G(1,2),2)+pow(G(0,3),2)*2.0*G(1,2)*G_jac3(1,2)-2.0*G(0,3)*G_jac3(0,3)*G(1,1)*G(2,2)-pow(G(0,3),2)*G_jac3(1,1)*G(2,2)-pow(G(0,3),2)*G(1,1)*G_jac3(2,2)-2.0*G_jac3(0,2)*G(0,3)*G(1,2)*G(1,3)-2.0*G(0,2)*G_jac3(0,3)*G(1,2)*G(1,3)-2.0*G(0,2)*G(0,3)*G_jac3(1,2)*G(1,3)-2.0*G(0,2)*G(0,3)*G(1,2)*G_jac3(1,3)+2.0*G_jac3(0,2)*G(0,3)*G(1,1)*G(2,3)+2.0*G(0,2)*G_jac3(0,3)*G(1,1)*G(2,3)+2.0*G(0,2)*G(0,3)*G_jac3(1,1)*G(2,3)+2.0*G(0,2)*G(0,3)*G(1,1)*G_jac3(2,3) +2.0*G(0,2)*G_jac3(0,2)*pow(G(1,3),2)+pow(G(0,2),2)*2.0*G(1,3)*G_jac3(1,3)-2.0*G(0,2)*G_jac3(0,2)*G(1,1)*G(3,3)-pow(G(0,2),2)*G_jac3(1,1)*G(3,3)-pow(G(0,2),2)*G(1,1)*G_jac3(3,3)+2.0*G_jac3(0,1)*G(0,3)*G(1,3)*G(2,2)+2.0*G(0,1)*G_jac3(0,3)*G(1,3)*G(2,2)+2.0*G(0,1)*G(0,3)*G_jac3(1,3)*G(2,2)+2.0*G(0,1)*G(0,3)*G(1,3)*G_jac3(2,2)-2.0*G_jac3(0,1)*G(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G_jac3(0,3)*G(1,2)*G(2,3)-2.0*G(0,1)*G(0,3)*G_jac3(1,2)*G(2,3)-2.0*G(0,1)*G(0,3)*G(1,2)*G_jac3(2,3)-2.0*G_jac3(0,1)*G(0,2)*G(1,3)*G(2,3)-2.0*G(0,1)*G_jac3(0,2)*G(1,3)*G(2,3)-2.0*G(0,1)*G(0,2)*G_jac3(1,3)*G(2,3)-2.0*G(0,1)*G(0,2)*G(1,3)*G_jac3(2,3)+2.0*G_jac3(0,1)*G(0,2)*G(1,2)*G(3,3)+2.0*G(0,1)*G_jac3(0,2)*G(1,2)*G(3,3)+2.0*G(0,1)*G(0,2)*G_jac3(1,2)*G(3,3)+2.0*G(0,1)*G(0,2)*G(1,2)*G_jac3(3,3)+2.0*G(0,1)*G_jac3(0,1)*pow(G(2,3),2)+pow(G(0,1),2)*2.0*G(2,3)*G_jac3(2,3)-2.0*G(0,1)*G_jac3(0,1)*G(2,2)*G(3,3)-pow(G(0,1),2)*G_jac3(2,2)*G(3,3)-pow(G(0,1),2)*G(2,2)*G_jac3(3,3)-G_jac3(0,0)*pow(G(1,3),2)*G(2,2)-G(0,0)*2.0*G(1,3)*G_jac3(1,3)*G(2,2)-G(0,0)*pow(G(1,3),2)*G_jac3(2,2)+2.0*G_jac3(0,0)*G(1,2)*G(1,3)*G(2,3)+2.0*G(0,0)*G_jac3(1,2)*G(1,3)*G(2,3)+2.0*G(0,0)*G(1,2)*G_jac3(1,3)*G(2,3)+2.0*G(0,0)*G(1,2)*G(1,3)*G_jac3(2,3)-G_jac3(0,0)*pow(G(1,2),2)*G(3,3)-G(0,0)*2.0*G(1,2)*G_jac3(1,2)*G(3,3)-G(0,0)*pow(G(1,2),2)*G_jac3(3,3)-G_jac3(0,0)*G(1,1)*pow(G(2,3),2)-G(0,0)*G_jac3(1,1)*pow(G(2,3),2)-G(0,0)*G(1,1)*2.0*G(2,3)*G_jac3(2,3)+G_jac3(0,0)*G(1,1)*G(2,2)*G(3,3)+G(0,0)*G_jac3(1,1)*G(2,2)*G(3,3)+G(0,0)*G(1,1)*G_jac3(2,2)*G(3,3)+G(0,0)*G(1,1)*G(2,2)*G_jac3(3,3); double B_pw2 = B*B; double B_pw2_jac1 = 2.0*B*B_jac1; double B_pw2_jac2 = 2.0*B*B_jac2; double B_pw2_jac3 = 2.0*B*B_jac3; double B_pw3 = B_pw2*B; double B_pw3_jac1 = 3.0*B_pw2*B_jac1; double B_pw3_jac2 = 3.0*B_pw2*B_jac2; double B_pw3_jac3 = 3.0*B_pw2*B_jac3; double B_pw4 = B_pw3*B; double B_pw4_jac1 = 4.0*B_pw3*B_jac1; double B_pw4_jac2 = 4.0*B_pw3*B_jac2; double B_pw4_jac3 = 4.0*B_pw3*B_jac3; double alpha = -3.0*B_pw2/8.0+C; double alpha_jac1 = -3.0*B_pw2_jac1/8.0+C_jac1; double alpha_jac2 = -3.0*B_pw2_jac2/8.0+C_jac2; double alpha_jac3 = -3.0*B_pw2_jac3/8.0+C_jac3; double beta = B_pw3/8.0-B*C/2.0+D; double beta_jac1 = B_pw3_jac1/8.0-(B_jac1*C+B*C_jac1)/2.0+D_jac1; double beta_jac2 = B_pw3_jac2/8.0-(B_jac2*C+B*C_jac2)/2.0+D_jac2; double beta_jac3 = B_pw3_jac3/8.0-(B_jac3*C+B*C_jac3)/2.0+D_jac3; double gamma = -3.0*B_pw4/256.0+B_pw2*C/16.0-B*D/4.0+E; double gamma_jac1 = -3.0*B_pw4_jac1/256.0+(B_pw2_jac1*C+B_pw2*C_jac1)/16.0-(B_jac1*D+B*D_jac1)/4.0+E_jac1; double gamma_jac2 = -3.0*B_pw4_jac2/256.0+(B_pw2_jac2*C+B_pw2*C_jac2)/16.0-(B_jac2*D+B*D_jac2)/4.0+E_jac2; double gamma_jac3 = -3.0*B_pw4_jac3/256.0+(B_pw2_jac3*C+B_pw2*C_jac3)/16.0-(B_jac3*D+B*D_jac3)/4.0+E_jac3; double alpha_pw2 = alpha*alpha; double alpha_pw2_jac1 = 2.0*alpha*alpha_jac1; double alpha_pw2_jac2 = 2.0*alpha*alpha_jac2; double alpha_pw2_jac3 = 2.0*alpha*alpha_jac3; double alpha_pw3 = alpha_pw2*alpha; double alpha_pw3_jac1 = 3.0*alpha_pw2*alpha_jac1; double alpha_pw3_jac2 = 3.0*alpha_pw2*alpha_jac2; double alpha_pw3_jac3 = 3.0*alpha_pw2*alpha_jac3; double p = -alpha_pw2/12.0-gamma; double p_jac1 = -alpha_pw2_jac1/12.0-gamma_jac1; double p_jac2 = -alpha_pw2_jac2/12.0-gamma_jac2; double p_jac3 = -alpha_pw2_jac3/12.0-gamma_jac3; double q = -alpha_pw3/108.0+alpha*gamma/3.0-pow(beta,2.0)/8.0; double q_jac1 = -alpha_pw3_jac1/108.0+(alpha_jac1*gamma+alpha*gamma_jac1)/3.0-2.0*beta*beta_jac1/8.0; double q_jac2 = -alpha_pw3_jac2/108.0+(alpha_jac2*gamma+alpha*gamma_jac2)/3.0-2.0*beta*beta_jac2/8.0; double q_jac3 = -alpha_pw3_jac3/108.0+(alpha_jac3*gamma+alpha*gamma_jac3)/3.0-2.0*beta*beta_jac3/8.0; double helper1 = -pow(p,3.0)/27.0; double helper1_jac1 = -3.0*pow(p,2.0)*p_jac1/27.0; double helper1_jac2 = -3.0*pow(p,2.0)*p_jac2/27.0; double helper1_jac3 = -3.0*pow(p,2.0)*p_jac3/27.0; double theta1 = pow( helper1, (1.0/6.0) ) * cos( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ); double theta1_jac1 = (1.0/6.0)*pow( helper1, (-5.0/6.0) ) * helper1_jac1 * cos( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ) - pow( helper1, (1.0/6.0) ) * sin( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ) * ( 2.0 * helper1 * q_jac1 - q * helper1_jac1) / ( 12.0 * pow(helper1,1.5) * sqrt(1.0 - q / (4.0*helper1) ) ) ; double theta1_jac2 = (1.0/6.0)*pow( helper1, (-5.0/6.0) ) * helper1_jac2 * cos( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ) - pow( helper1, (1.0/6.0) ) * sin( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ) * ( 2.0 * helper1 * q_jac2 - q * helper1_jac2) / ( 12.0 * pow(helper1,1.5) * sqrt(1.0 - q / (4.0*helper1) ) ) ; double theta1_jac3 = (1.0/6.0)*pow( helper1, (-5.0/6.0) ) * helper1_jac3 * cos( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ) - pow( helper1, (1.0/6.0) ) * sin( (1.0/3.0) * acos( (-q/2.0) / sqrt(helper1) ) ) * ( 2.0 * helper1 * q_jac3 - q * helper1_jac3) / ( 12.0 * pow(helper1,1.5) * sqrt(1.0 - q / (4.0*helper1) ) ) ; double theta2 = pow( helper1 , (1.0/3.0) ); double theta2_jac1 = (1.0/3.0) * pow( helper1 , (-2.0/3.0) ) * helper1_jac1; double theta2_jac2 = (1.0/3.0) * pow( helper1 , (-2.0/3.0) ) * helper1_jac2; double theta2_jac3 = (1.0/3.0) * pow( helper1 , (-2.0/3.0) ) * helper1_jac3; double y = -(5.0/6.0)*alpha - ( (1.0/3.0) * p * theta1 - theta1 * theta2) / theta2; double y_jac1 = -(5.0/6.0)*alpha_jac1 - ( ( (1.0/3.0) * p_jac1 * theta1 + (1.0/3.0) * p * theta1_jac1 - theta1_jac1 * theta2 - theta1 * theta2_jac1 )*theta2 - ( (1.0/3.0) * p * theta1 - theta1 * theta2) * theta2_jac1 ) / pow(theta2,2.0); double y_jac2 = -(5.0/6.0)*alpha_jac2 - ( ( (1.0/3.0) * p_jac2 * theta1 + (1.0/3.0) * p * theta1_jac2 - theta1_jac2 * theta2 - theta1 * theta2_jac2 )*theta2 - ( (1.0/3.0) * p * theta1 - theta1 * theta2) * theta2_jac2 ) / pow(theta2,2.0); double y_jac3 = -(5.0/6.0)*alpha_jac3 - ( ( (1.0/3.0) * p_jac3 * theta1 + (1.0/3.0) * p * theta1_jac3 - theta1_jac3 * theta2 - theta1 * theta2_jac3 )*theta2 - ( (1.0/3.0) * p * theta1 - theta1 * theta2) * theta2_jac3 ) / pow(theta2,2.0); double w = sqrt(alpha+2.0*y); double w_jac1 = (alpha_jac1 + 2.0*y_jac1)/(2.0*sqrt(alpha+2.0*y)); double w_jac2 = (alpha_jac2 + 2.0*y_jac2)/(2.0*sqrt(alpha+2.0*y)); double w_jac3 = (alpha_jac3 + 2.0*y_jac3)/(2.0*sqrt(alpha+2.0*y)); double smallestEV = -B/4.0 -0.5*w -0.5*sqrt(-3.0*alpha-2.0*y+2.0*beta/w); jacobian[0] = -B_jac1/4.0 -0.5*w_jac1 -0.25*( -3.0*alpha_jac1-2.0*y_jac1+2.0*(beta_jac1*w-beta*w_jac1)/pow(w,2.0) )/sqrt(-3.0*alpha-2.0*y+2.0*beta/w); jacobian[1] = -B_jac2/4.0 -0.5*w_jac2 -0.25*( -3.0*alpha_jac2-2.0*y_jac2+2.0*(beta_jac2*w-beta*w_jac2)/pow(w,2.0) )/sqrt(-3.0*alpha-2.0*y+2.0*beta/w); jacobian[2] = -B_jac3/4.0 -0.5*w_jac3 -0.25*( -3.0*alpha_jac3-2.0*y_jac3+2.0*(beta_jac3*w-beta*w_jac3)/pow(w,2.0) )/sqrt(-3.0*alpha-2.0*y+2.0*beta/w); return smallestEV; */ /////////////////////////////////////////////////////// end of Method 1 /////////////////////////////////////////////////////////////////////////////////// double opengv::relative_pose::modules::ge:: getCostWithJacobian( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, Eigen::Matrix & jacobian, int step ) { double eps = 0.00000001; double cost = getCost(xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley,step); for( int j = 0; j < 3; j++ ) { cayley_t cayley_j = cayley; cayley_j[j] += eps; double cost_j = getCost(xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley_j,step); cayley_j = cayley; cayley_j[j] -= eps; double cost_jm = getCost(xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley_j,step); jacobian(0,j) = (cost_j - cost_jm); //division by eps can be ommited } return cost; } void opengv::relative_pose::modules::ge::getQuickJacobian( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, double currentValue, Eigen::Matrix & jacobian, int step ) { double eps = 0.00000001; for( int j = 0; j < 3; j++ ) { cayley_t cayley_j = cayley; cayley_j[j] += eps; double cost_j = getCost(xxF,yyF,zzF,xyF,yzF,zxF,x1P,y1P,z1P,x2P,y2P,z2P,m11P,m12P,m22P,cayley_j,step); jacobian(0,j) = (cost_j - currentValue); //division by eps can be ommited } } Eigen::Matrix4d opengv::relative_pose::modules::ge::composeG( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley) { Eigen::Matrix4d G; rotation_t R = math::cayley2rot_reduced(cayley); //todo: Fill the matrix G using the precomputed summation terms Eigen::Vector3d xxFr1t = xxF*R.row(1).transpose(); Eigen::Vector3d yyFr0t = yyF*R.row(0).transpose(); Eigen::Vector3d zzFr0t = zzF*R.row(0).transpose(); Eigen::Vector3d yzFr0t = yzF*R.row(0).transpose(); Eigen::Vector3d xyFr1t = xyF*R.row(1).transpose(); Eigen::Vector3d xyFr2t = xyF*R.row(2).transpose(); Eigen::Vector3d zxFr1t = zxF*R.row(1).transpose(); Eigen::Vector3d zxFr2t = zxF*R.row(2).transpose(); double temp; temp = R.row(2)*yyF*R.row(2).transpose(); G(0,0) = temp; temp = -2.0*R.row(2)*yzF*R.row(1).transpose(); G(0,0) += temp; temp = R.row(1)*zzF*R.row(1).transpose(); G(0,0) += temp; temp = R.row(2)*yzFr0t; G(0,1) = temp; temp = -1.0*R.row(2)*xyFr2t; G(0,1) += temp; temp = -1.0*R.row(1)*zzFr0t; G(0,1) += temp; temp = R.row(1)*zxFr2t; G(0,1) += temp; temp = R.row(2)*xyFr1t; G(0,2) = temp; temp = -1.0*R.row(2)*yyFr0t; G(0,2) += temp; temp = -1.0*R.row(1)*zxFr1t; G(0,2) += temp; temp = R.row(1)*yzFr0t; G(0,2) += temp; temp = R.row(0)*zzFr0t; G(1,1) = temp; temp = -2.0*R.row(0)*zxFr2t; G(1,1) += temp; temp = R.row(2)*xxF*R.row(2).transpose(); G(1,1) += temp; temp = R.row(0)*zxFr1t; G(1,2) = temp; temp = -1.0*R.row(0)*yzFr0t; G(1,2) += temp; temp = -1.0*R.row(2)*xxFr1t; G(1,2) += temp; temp = R.row(0)*xyFr2t; G(1,2) += temp; temp = R.row(1)*xxFr1t; G(2,2) = temp; temp = -2.0*R.row(0)*xyFr1t; G(2,2) += temp; temp = R.row(0)*yyFr0t; G(2,2) += temp; G(1,0) = G(0,1); G(2,0) = G(0,2); G(2,1) = G(1,2); //the generalized terms: Eigen::Matrix Rows; Rows.block<1,3>(0,0) = R.row(0); Rows.block<1,3>(0,3) = R.row(1); Rows.block<1,3>(0,6) = R.row(2); Eigen::Matrix Rowst = Rows.transpose(); Eigen::Matrix Cols; Cols.block<3,1>(0,0) = R.col(0); Cols.block<3,1>(3,0) = R.col(1); Cols.block<3,1>(6,0) = R.col(2); Eigen::Vector3d x1PC = x1P*Cols; Eigen::Vector3d y1PC = y1P*Cols; Eigen::Vector3d z1PC = z1P*Cols; Eigen::Vector3d x2PR = x2P*Rowst; Eigen::Vector3d y2PR = y2P*Rowst; Eigen::Vector3d z2PR = z2P*Rowst; temp = R.row(2)*y1PC; G(0,3) = temp; temp = R.row(2)*y2PR; G(0,3) += temp; temp = -1.0*R.row(1)*z1PC; G(0,3) += temp; temp = -1.0*R.row(1)*z2PR; G(0,3) += temp; temp = R.row(0)*z1PC; G(1,3) = temp; temp = R.row(0)*z2PR; G(1,3) += temp; temp = -1.0*R.row(2)*x1PC; G(1,3) += temp; temp = -1.0*R.row(2)*x2PR; G(1,3) += temp; temp = R.row(1)*x1PC; G(2,3) = temp; temp = R.row(1)*x2PR; G(2,3) += temp; temp = -1.0*R.row(0)*y1PC; G(2,3) += temp; temp = -1.0*R.row(0)*y2PR; G(2,3) += temp; temp = -1.0*Cols.transpose()*m11P*Cols; G(3,3) = temp; temp = -1.0*Rows*m22P*Rowst; G(3,3) += temp; temp = -2.0*Rows*m12P*Cols; G(3,3) += temp; G(3,0) = G(0,3); G(3,1) = G(1,3); G(3,2) = G(2,3); return G; } Eigen::Matrix4d opengv::relative_pose::modules::ge::composeGwithJacobians( const Eigen::Matrix3d & xxF, const Eigen::Matrix3d & yyF, const Eigen::Matrix3d & zzF, const Eigen::Matrix3d & xyF, const Eigen::Matrix3d & yzF, const Eigen::Matrix3d & zxF, const Eigen::Matrix & x1P, const Eigen::Matrix & y1P, const Eigen::Matrix & z1P, const Eigen::Matrix & x2P, const Eigen::Matrix & y2P, const Eigen::Matrix & z2P, const Eigen::Matrix & m11P, const Eigen::Matrix & m12P, const Eigen::Matrix & m22P, const cayley_t & cayley, Eigen::Matrix4d & G_jac1, Eigen::Matrix4d & G_jac2, Eigen::Matrix4d & G_jac3 ) { rotation_t R = math::cayley2rot_reduced(cayley); rotation_t R_jac1; rotation_t R_jac2; rotation_t R_jac3; R_jac1(0,0) = 2.0*cayley[0]; R_jac1(0,1) = 2.0*cayley[1]; R_jac1(0,2) = 2.0*cayley[2]; R_jac1(1,0) = 2.0*cayley[1]; R_jac1(1,1) = -2.0*cayley[0]; R_jac1(1,2) = -2.0; R_jac1(2,0) = 2.0*cayley[2]; R_jac1(2,1) = 2.0; R_jac1(2,2) = -2.0*cayley[0]; R_jac2(0,0) = -2.0*cayley[1]; R_jac2(0,1) = 2.0*cayley[0]; R_jac2(0,2) = 2.0; R_jac2(1,0) = 2.0*cayley[0]; R_jac2(1,1) = 2.0*cayley[1]; R_jac2(1,2) = 2.0*cayley[2]; R_jac2(2,0) = -2.0; R_jac2(2,1) = 2.0*cayley[2]; R_jac2(2,2) = -2.0*cayley[1]; R_jac3(0,0) = -2.0*cayley[2]; R_jac3(0,1) = -2.0; R_jac3(0,2) = 2.0*cayley[0]; R_jac3(1,0) = 2.0; R_jac3(1,1) = -2.0*cayley[2]; R_jac3(1,2) = 2.0*cayley[1]; R_jac3(2,0) = 2.0*cayley[0]; R_jac3(2,1) = 2.0*cayley[1]; R_jac3(2,2) = 2.0*cayley[2]; //Fill the matrix G using the precomputed summation terms. Plus Jacobian. Eigen::Matrix4d G; double temp; temp = R.row(2)*yyF*R.row(2).transpose(); G(0,0) = temp; temp = -2.0*R.row(2)*yzF*R.row(1).transpose(); G(0,0) += temp; temp = R.row(1)*zzF*R.row(1).transpose(); G(0,0) += temp; temp = 2.0*R_jac1.row(2)*yyF*R.row(2).transpose(); G_jac1(0,0) = temp; temp = -2.0*R_jac1.row(2)*yzF*R.row(1).transpose(); G_jac1(0,0) += temp; temp = -2.0*R.row(2)*yzF*R_jac1.row(1).transpose(); G_jac1(0,0) += temp; temp = 2.0*R_jac1.row(1)*zzF*R.row(1).transpose(); G_jac1(0,0) += temp; temp = 2.0*R_jac2.row(2)*yyF*R.row(2).transpose(); G_jac2(0,0) = temp; temp = -2.0*R_jac2.row(2)*yzF*R.row(1).transpose(); G_jac2(0,0) += temp; temp = -2.0*R.row(2)*yzF*R_jac2.row(1).transpose(); G_jac2(0,0) += temp; temp = 2.0*R_jac2.row(1)*zzF*R.row(1).transpose(); G_jac2(0,0) += temp; temp = 2.0*R_jac3.row(2)*yyF*R.row(2).transpose(); G_jac3(0,0) = temp; temp = -2.0*R_jac3.row(2)*yzF*R.row(1).transpose(); G_jac3(0,0) += temp; temp = -2.0*R.row(2)*yzF*R_jac3.row(1).transpose(); G_jac3(0,0) += temp; temp = 2.0*R_jac3.row(1)*zzF*R.row(1).transpose(); G_jac3(0,0) += temp; temp = R.row(2)*yzF*R.row(0).transpose(); G(0,1) = temp; temp = -1.0*R.row(2)*xyF*R.row(2).transpose(); G(0,1) += temp; temp = -1.0*R.row(1)*zzF*R.row(0).transpose(); G(0,1) += temp; temp = R.row(1)*zxF*R.row(2).transpose(); G(0,1) += temp; temp = R_jac1.row(2)*yzF*R.row(0).transpose(); G_jac1(0,1) = temp; temp = R.row(2)*yzF*R_jac1.row(0).transpose(); G_jac1(0,1) += temp; temp = -2.0*R_jac1.row(2)*xyF*R.row(2).transpose(); G_jac1(0,1) += temp; temp = -R_jac1.row(1)*zzF*R.row(0).transpose(); G_jac1(0,1) += temp; temp = -R.row(1)*zzF*R_jac1.row(0).transpose(); G_jac1(0,1) += temp; temp = R_jac1.row(1)*zxF*R.row(2).transpose(); G_jac1(0,1) += temp; temp = R.row(1)*zxF*R_jac1.row(2).transpose(); G_jac1(0,1) += temp; temp = R_jac2.row(2)*yzF*R.row(0).transpose(); G_jac2(0,1) = temp; temp = R.row(2)*yzF*R_jac2.row(0).transpose(); G_jac2(0,1) += temp; temp = -2.0*R_jac2.row(2)*xyF*R.row(2).transpose(); G_jac2(0,1) += temp; temp = -R_jac2.row(1)*zzF*R.row(0).transpose(); G_jac2(0,1) += temp; temp = -R.row(1)*zzF*R_jac2.row(0).transpose(); G_jac2(0,1) += temp; temp = R_jac2.row(1)*zxF*R.row(2).transpose(); G_jac2(0,1) += temp; temp = R.row(1)*zxF*R_jac2.row(2).transpose(); G_jac2(0,1) += temp; temp = R_jac3.row(2)*yzF*R.row(0).transpose(); G_jac3(0,1) = temp; temp = R.row(2)*yzF*R_jac3.row(0).transpose(); G_jac3(0,1) += temp; temp = -2.0*R_jac3.row(2)*xyF*R.row(2).transpose(); G_jac3(0,1) += temp; temp = -R_jac3.row(1)*zzF*R.row(0).transpose(); G_jac3(0,1) += temp; temp = -R.row(1)*zzF*R_jac3.row(0).transpose(); G_jac3(0,1) += temp; temp = R_jac3.row(1)*zxF*R.row(2).transpose(); G_jac3(0,1) += temp; temp = R.row(1)*zxF*R_jac3.row(2).transpose(); G_jac3(0,1) += temp; temp = R.row(2)*xyF*R.row(1).transpose(); G(0,2) = temp; temp = -1.0*R.row(2)*yyF*R.row(0).transpose(); G(0,2) += temp; temp = -1.0*R.row(1)*zxF*R.row(1).transpose(); G(0,2) += temp; temp = R.row(1)*yzF*R.row(0).transpose(); G(0,2) += temp; temp = R_jac1.row(2)*xyF*R.row(1).transpose(); G_jac1(0,2) = temp; temp = R.row(2)*xyF*R_jac1.row(1).transpose(); G_jac1(0,2) += temp; temp = -R_jac1.row(2)*yyF*R.row(0).transpose(); G_jac1(0,2) += temp; temp = -R.row(2)*yyF*R_jac1.row(0).transpose(); G_jac1(0,2) += temp; temp = -2.0*R_jac1.row(1)*zxF*R.row(1).transpose(); G_jac1(0,2) += temp; temp = R_jac1.row(1)*yzF*R.row(0).transpose(); G_jac1(0,2) += temp; temp = R.row(1)*yzF*R_jac1.row(0).transpose(); G_jac1(0,2) += temp; temp = R_jac2.row(2)*xyF*R.row(1).transpose(); G_jac2(0,2) = temp; temp = R.row(2)*xyF*R_jac2.row(1).transpose(); G_jac2(0,2) += temp; temp = -R_jac2.row(2)*yyF*R.row(0).transpose(); G_jac2(0,2) += temp; temp = -R.row(2)*yyF*R_jac2.row(0).transpose(); G_jac2(0,2) += temp; temp = -2.0*R_jac2.row(1)*zxF*R.row(1).transpose(); G_jac2(0,2) += temp; temp = R_jac2.row(1)*yzF*R.row(0).transpose(); G_jac2(0,2) += temp; temp = R.row(1)*yzF*R_jac2.row(0).transpose(); G_jac2(0,2) += temp; temp = R_jac3.row(2)*xyF*R.row(1).transpose(); G_jac3(0,2) = temp; temp = R.row(2)*xyF*R_jac3.row(1).transpose(); G_jac3(0,2) += temp; temp = -R_jac3.row(2)*yyF*R.row(0).transpose(); G_jac3(0,2) += temp; temp = -R.row(2)*yyF*R_jac3.row(0).transpose(); G_jac3(0,2) += temp; temp = -2.0*R_jac3.row(1)*zxF*R.row(1).transpose(); G_jac3(0,2) += temp; temp = R_jac3.row(1)*yzF*R.row(0).transpose(); G_jac3(0,2) += temp; temp = R.row(1)*yzF*R_jac3.row(0).transpose(); G_jac3(0,2) += temp; temp = R.row(0)*zzF*R.row(0).transpose(); G(1,1) = temp; temp = -2.0*R.row(0)*zxF*R.row(2).transpose(); G(1,1) += temp; temp = R.row(2)*xxF*R.row(2).transpose(); G(1,1) += temp; temp = 2.0*R_jac1.row(0)*zzF*R.row(0).transpose(); G_jac1(1,1) = temp; temp = -2.0*R_jac1.row(0)*zxF*R.row(2).transpose(); G_jac1(1,1) += temp; temp = -2.0*R.row(0)*zxF*R_jac1.row(2).transpose(); G_jac1(1,1) += temp; temp = 2.0*R_jac1.row(2)*xxF*R.row(2).transpose(); G_jac1(1,1) += temp; temp = 2.0*R_jac2.row(0)*zzF*R.row(0).transpose(); G_jac2(1,1) = temp; temp = -2.0*R_jac2.row(0)*zxF*R.row(2).transpose(); G_jac2(1,1) += temp; temp = -2.0*R.row(0)*zxF*R_jac2.row(2).transpose(); G_jac2(1,1) += temp; temp = 2.0*R_jac2.row(2)*xxF*R.row(2).transpose(); G_jac2(1,1) += temp; temp = 2.0*R_jac3.row(0)*zzF*R.row(0).transpose(); G_jac3(1,1) = temp; temp = -2.0*R_jac3.row(0)*zxF*R.row(2).transpose(); G_jac3(1,1) += temp; temp = -2.0*R.row(0)*zxF*R_jac3.row(2).transpose(); G_jac3(1,1) += temp; temp = 2.0*R_jac3.row(2)*xxF*R.row(2).transpose(); G_jac3(1,1) += temp; temp = R.row(0)*zxF*R.row(1).transpose(); G(1,2) = temp; temp = -1.0*R.row(0)*yzF*R.row(0).transpose(); G(1,2) += temp; temp = -1.0*R.row(2)*xxF*R.row(1).transpose(); G(1,2) += temp; temp = R.row(2)*xyF*R.row(0).transpose(); G(1,2) += temp; temp = R_jac1.row(0)*zxF*R.row(1).transpose(); G_jac1(1,2) = temp; temp = R.row(0)*zxF*R_jac1.row(1).transpose(); G_jac1(1,2) += temp; temp = -2.0*R_jac1.row(0)*yzF*R.row(0).transpose(); G_jac1(1,2) += temp; temp = -R_jac1.row(2)*xxF*R.row(1).transpose(); G_jac1(1,2) += temp; temp = -R.row(2)*xxF*R_jac1.row(1).transpose(); G_jac1(1,2) += temp; temp = R_jac1.row(2)*xyF*R.row(0).transpose(); G_jac1(1,2) += temp; temp = R.row(2)*xyF*R_jac1.row(0).transpose(); G_jac1(1,2) += temp; temp = R_jac2.row(0)*zxF*R.row(1).transpose(); G_jac2(1,2) = temp; temp = R.row(0)*zxF*R_jac2.row(1).transpose(); G_jac2(1,2) += temp; temp = -2.0*R_jac2.row(0)*yzF*R.row(0).transpose(); G_jac2(1,2) += temp; temp = -R_jac2.row(2)*xxF*R.row(1).transpose(); G_jac2(1,2) += temp; temp = -R.row(2)*xxF*R_jac2.row(1).transpose(); G_jac2(1,2) += temp; temp = R_jac2.row(2)*xyF*R.row(0).transpose(); G_jac2(1,2) += temp; temp = R.row(2)*xyF*R_jac2.row(0).transpose(); G_jac2(1,2) += temp; temp = R_jac3.row(0)*zxF*R.row(1).transpose(); G_jac3(1,2) = temp; temp = R.row(0)*zxF*R_jac3.row(1).transpose(); G_jac3(1,2) += temp; temp = -2.0*R_jac3.row(0)*yzF*R.row(0).transpose(); G_jac3(1,2) += temp; temp = -R_jac3.row(2)*xxF*R.row(1).transpose(); G_jac3(1,2) += temp; temp = -R.row(2)*xxF*R_jac3.row(1).transpose(); G_jac3(1,2) += temp; temp = R_jac3.row(2)*xyF*R.row(0).transpose(); G_jac3(1,2) += temp; temp = R.row(2)*xyF*R_jac3.row(0).transpose(); G_jac3(1,2) += temp; temp = R.row(1)*xxF*R.row(1).transpose(); G(2,2) = temp; temp = -2.0*R.row(0)*xyF*R.row(1).transpose(); G(2,2) += temp; temp = R.row(0)*yyF*R.row(0).transpose(); G(2,2) += temp; temp = 2.0*R_jac1.row(1)*xxF*R.row(1).transpose(); G_jac1(2,2) = temp; temp = -2.0*R_jac1.row(0)*xyF*R.row(1).transpose(); G_jac1(2,2) += temp; temp = -2.0*R.row(0)*xyF*R_jac1.row(1).transpose(); G_jac1(2,2) += temp; temp = 2.0*R_jac1.row(0)*yyF*R.row(0).transpose(); G_jac1(2,2) += temp; temp = 2.0*R_jac2.row(1)*xxF*R.row(1).transpose(); G_jac2(2,2) = temp; temp = -2.0*R_jac2.row(0)*xyF*R.row(1).transpose(); G_jac2(2,2) += temp; temp = -2.0*R.row(0)*xyF*R_jac2.row(1).transpose(); G_jac2(2,2) += temp; temp = 2.0*R_jac2.row(0)*yyF*R.row(0).transpose(); G_jac2(2,2) += temp; temp = 2.0*R_jac3.row(1)*xxF*R.row(1).transpose(); G_jac3(2,2) = temp; temp = -2.0*R_jac3.row(0)*xyF*R.row(1).transpose(); G_jac3(2,2) += temp; temp = -2.0*R.row(0)*xyF*R_jac3.row(1).transpose(); G_jac3(2,2) += temp; temp = 2.0*R_jac3.row(0)*yyF*R.row(0).transpose(); G_jac3(2,2) += temp; G(1,0) = G(0,1); G(2,0) = G(0,2); G(2,1) = G(1,2); G_jac1(1,0) = G_jac1(0,1); G_jac1(2,0) = G_jac1(0,2); G_jac1(2,1) = G_jac1(1,2); G_jac2(1,0) = G_jac2(0,1); G_jac2(2,0) = G_jac2(0,2); G_jac2(2,1) = G_jac2(1,2); G_jac3(1,0) = G_jac3(0,1); G_jac3(2,0) = G_jac3(0,2); G_jac3(2,1) = G_jac3(1,2); //the generalized terms: Eigen::Matrix Rows; Rows.block<1,3>(0,0) = R.row(0); Rows.block<1,3>(0,3) = R.row(1); Rows.block<1,3>(0,6) = R.row(2); Eigen::Matrix Cols; Cols.block<3,1>(0,0) = R.col(0); Cols.block<3,1>(3,0) = R.col(1); Cols.block<3,1>(6,0) = R.col(2); Eigen::Matrix Rows_jac1; Rows_jac1.block<1,3>(0,0) = R_jac1.row(0); Rows_jac1.block<1,3>(0,3) = R_jac1.row(1); Rows_jac1.block<1,3>(0,6) = R_jac1.row(2); Eigen::Matrix Rows_jac2; Rows_jac2.block<1,3>(0,0) = R_jac2.row(0); Rows_jac2.block<1,3>(0,3) = R_jac2.row(1); Rows_jac2.block<1,3>(0,6) = R_jac2.row(2); Eigen::Matrix Rows_jac3; Rows_jac3.block<1,3>(0,0) = R_jac3.row(0); Rows_jac3.block<1,3>(0,3) = R_jac3.row(1); Rows_jac3.block<1,3>(0,6) = R_jac3.row(2); Eigen::Matrix Cols_jac1; Cols_jac1.block<3,1>(0,0) = R_jac1.col(0); Cols_jac1.block<3,1>(3,0) = R_jac1.col(1); Cols_jac1.block<3,1>(6,0) = R_jac1.col(2); Eigen::Matrix Cols_jac2; Cols_jac2.block<3,1>(0,0) = R_jac2.col(0); Cols_jac2.block<3,1>(3,0) = R_jac2.col(1); Cols_jac2.block<3,1>(6,0) = R_jac2.col(2); Eigen::Matrix Cols_jac3; Cols_jac3.block<3,1>(0,0) = R_jac3.col(0); Cols_jac3.block<3,1>(3,0) = R_jac3.col(1); Cols_jac3.block<3,1>(6,0) = R_jac3.col(2); temp = R.row(2)*y1P*Cols; G(0,3) = temp; temp = R.row(2)*y2P*Rows.transpose(); G(0,3) += temp; temp = -1.0*R.row(1)*z1P*Cols; G(0,3) += temp; temp = -1.0*R.row(1)*z2P*Rows.transpose(); G(0,3) += temp; temp = R_jac1.row(2)*y1P*Cols; G_jac1(0,3) = temp; temp = R.row(2)*y1P*Cols_jac1; G_jac1(0,3) += temp; temp = R_jac1.row(2)*y2P*Rows.transpose(); G_jac1(0,3) += temp; temp = R.row(2)*y2P*Rows_jac1.transpose(); G_jac1(0,3) += temp; temp = -1.0*R_jac1.row(1)*z1P*Cols; G_jac1(0,3) += temp; temp = -1.0*R.row(1)*z1P*Cols_jac1; G_jac1(0,3) += temp; temp = -1.0*R_jac1.row(1)*z2P*Rows.transpose(); G_jac1(0,3) += temp; temp = -1.0*R.row(1)*z2P*Rows_jac1.transpose(); G_jac1(0,3) += temp; temp = R_jac2.row(2)*y1P*Cols; G_jac2(0,3) = temp; temp = R.row(2)*y1P*Cols_jac2; G_jac2(0,3) += temp; temp = R_jac2.row(2)*y2P*Rows.transpose(); G_jac2(0,3) += temp; temp = R.row(2)*y2P*Rows_jac2.transpose(); G_jac2(0,3) += temp; temp = -1.0*R_jac2.row(1)*z1P*Cols; G_jac2(0,3) += temp; temp = -1.0*R.row(1)*z1P*Cols_jac2; G_jac2(0,3) += temp; temp = -1.0*R_jac2.row(1)*z2P*Rows.transpose(); G_jac2(0,3) += temp; temp = -1.0*R.row(1)*z2P*Rows_jac2.transpose(); G_jac2(0,3) += temp; temp = R_jac3.row(2)*y1P*Cols; G_jac3(0,3) = temp; temp = R.row(2)*y1P*Cols_jac3; G_jac3(0,3) += temp; temp = R_jac3.row(2)*y2P*Rows.transpose(); G_jac3(0,3) += temp; temp = R.row(2)*y2P*Rows_jac3.transpose(); G_jac3(0,3) += temp; temp = -1.0*R_jac3.row(1)*z1P*Cols; G_jac3(0,3) += temp; temp = -1.0*R.row(1)*z1P*Cols_jac3; G_jac3(0,3) += temp; temp = -1.0*R_jac3.row(1)*z2P*Rows.transpose(); G_jac3(0,3) += temp; temp = -1.0*R.row(1)*z2P*Rows_jac3.transpose(); G_jac3(0,3) += temp; temp = R.row(0)*z1P*Cols; G(1,3) = temp; temp = R.row(0)*z2P*Rows.transpose(); G(1,3) += temp; temp = -1.0*R.row(2)*x1P*Cols; G(1,3) += temp; temp = -1.0*R.row(2)*x2P*Rows.transpose(); G(1,3) += temp; temp = R_jac1.row(0)*z1P*Cols; G_jac1(1,3) = temp; temp = R.row(0)*z1P*Cols_jac1; G_jac1(1,3) += temp; temp = R_jac1.row(0)*z2P*Rows.transpose(); G_jac1(1,3) += temp; temp = R.row(0)*z2P*Rows_jac1.transpose(); G_jac1(1,3) += temp; temp = -1.0*R_jac1.row(2)*x1P*Cols; G_jac1(1,3) += temp; temp = -1.0*R.row(2)*x1P*Cols_jac1; G_jac1(1,3) += temp; temp = -1.0*R_jac1.row(2)*x2P*Rows.transpose(); G_jac1(1,3) += temp; temp = -1.0*R.row(2)*x2P*Rows_jac1.transpose(); G_jac1(1,3) += temp; temp = R_jac2.row(0)*z1P*Cols; G_jac2(1,3) = temp; temp = R.row(0)*z1P*Cols_jac2; G_jac2(1,3) += temp; temp = R_jac2.row(0)*z2P*Rows.transpose(); G_jac2(1,3) += temp; temp = R.row(0)*z2P*Rows_jac2.transpose(); G_jac2(1,3) += temp; temp = -1.0*R_jac2.row(2)*x1P*Cols; G_jac2(1,3) += temp; temp = -1.0*R.row(2)*x1P*Cols_jac2; G_jac2(1,3) += temp; temp = -1.0*R_jac2.row(2)*x2P*Rows.transpose(); G_jac2(1,3) += temp; temp = -1.0*R.row(2)*x2P*Rows_jac2.transpose(); G_jac2(1,3) += temp; temp = R_jac3.row(0)*z1P*Cols; G_jac3(1,3) = temp; temp = R.row(0)*z1P*Cols_jac3; G_jac3(1,3) += temp; temp = R_jac3.row(0)*z2P*Rows.transpose(); G_jac3(1,3) += temp; temp = R.row(0)*z2P*Rows_jac3.transpose(); G_jac3(1,3) += temp; temp = -1.0*R_jac3.row(2)*x1P*Cols; G_jac3(1,3) += temp; temp = -1.0*R.row(2)*x1P*Cols_jac3; G_jac3(1,3) += temp; temp = -1.0*R_jac3.row(2)*x2P*Rows.transpose(); G_jac3(1,3) += temp; temp = -1.0*R.row(2)*x2P*Rows_jac3.transpose(); G_jac3(1,3) += temp; temp = R.row(1)*x1P*Cols; G(2,3) = temp; temp = R.row(1)*x2P*Rows.transpose(); G(2,3) += temp; temp = -1.0*R.row(0)*y1P*Cols; G(2,3) += temp; temp = -1.0*R.row(0)*y2P*Rows.transpose(); G(2,3) += temp; temp = R_jac1.row(1)*x1P*Cols; G_jac1(2,3) = temp; temp = R.row(1)*x1P*Cols_jac1; G_jac1(2,3) += temp; temp = R_jac1.row(1)*x2P*Rows.transpose(); G_jac1(2,3) += temp; temp = R.row(1)*x2P*Rows_jac1.transpose(); G_jac1(2,3) += temp; temp = -1.0*R_jac1.row(0)*y1P*Cols; G_jac1(2,3) += temp; temp = -1.0*R.row(0)*y1P*Cols_jac1; G_jac1(2,3) += temp; temp = -1.0*R_jac1.row(0)*y2P*Rows.transpose(); G_jac1(2,3) += temp; temp = -1.0*R.row(0)*y2P*Rows_jac1.transpose(); G_jac1(2,3) += temp; temp = R_jac2.row(1)*x1P*Cols; G_jac2(2,3) = temp; temp = R.row(1)*x1P*Cols_jac2; G_jac2(2,3) += temp; temp = R_jac2.row(1)*x2P*Rows.transpose(); G_jac2(2,3) += temp; temp = R.row(1)*x2P*Rows_jac2.transpose(); G_jac2(2,3) += temp; temp = -1.0*R_jac2.row(0)*y1P*Cols; G_jac2(2,3) += temp; temp = -1.0*R.row(0)*y1P*Cols_jac2; G_jac2(2,3) += temp; temp = -1.0*R_jac2.row(0)*y2P*Rows.transpose(); G_jac2(2,3) += temp; temp = -1.0*R.row(0)*y2P*Rows_jac2.transpose(); G_jac2(2,3) += temp; temp = R_jac3.row(1)*x1P*Cols; G_jac3(2,3) = temp; temp = R.row(1)*x1P*Cols_jac3; G_jac3(2,3) += temp; temp = R_jac3.row(1)*x2P*Rows.transpose(); G_jac3(2,3) += temp; temp = R.row(1)*x2P*Rows_jac3.transpose(); G_jac3(2,3) += temp; temp = -1.0*R_jac3.row(0)*y1P*Cols; G_jac3(2,3) += temp; temp = -1.0*R.row(0)*y1P*Cols_jac3; G_jac3(2,3) += temp; temp = -1.0*R_jac3.row(0)*y2P*Rows.transpose(); G_jac3(2,3) += temp; temp = -1.0*R.row(0)*y2P*Rows_jac3.transpose(); G_jac3(2,3) += temp; temp = -1.0*Cols.transpose()*m11P*Cols; G(3,3) = temp; temp = -1.0*Rows*m22P*Rows.transpose(); G(3,3) += temp; temp = -2.0*Rows*m12P*Cols; G(3,3) += temp; temp = -2.0*Cols.transpose()*m11P*Cols_jac1; G_jac1(3,3) = temp; temp = -2.0*Rows_jac1*m22P*Rows.transpose(); G_jac1(3,3) += temp; temp = -2.0*Rows_jac1*m12P*Cols; G_jac1(3,3) += temp; temp = -2.0*Rows*m12P*Cols_jac1; G_jac1(3,3) += temp; temp = -2.0*Cols.transpose()*m11P*Cols_jac2; G_jac2(3,3) = temp; temp = -2.0*Rows_jac2*m22P*Rows.transpose(); G_jac2(3,3) += temp; temp = -2.0*Rows_jac2*m12P*Cols; G_jac2(3,3) += temp; temp = -2.0*Rows*m12P*Cols_jac2; G_jac2(3,3) += temp; temp = -2.0*Cols.transpose()*m11P*Cols_jac3; G_jac3(3,3) = temp; temp = -2.0*Rows_jac3*m22P*Rows.transpose(); G_jac3(3,3) += temp; temp = -2.0*Rows_jac3*m12P*Cols; G_jac3(3,3) += temp; temp = -2.0*Rows*m12P*Cols_jac3; G_jac3(3,3) += temp; G(3,0) = G(0,3); G(3,1) = G(1,3); G(3,2) = G(2,3); G_jac1(3,0) = G_jac1(0,3); G_jac1(3,1) = G_jac1(1,3); G_jac1(3,2) = G_jac1(2,3); G_jac2(3,0) = G_jac2(0,3); G_jac2(3,1) = G_jac2(1,3); G_jac2(3,2) = G_jac2(2,3); G_jac3(3,0) = G_jac3(0,3); G_jac3(3,1) = G_jac3(1,3); G_jac3(3,2) = G_jac3(2,3); return G; } opengv/src/relative_pose/CentralRelativeWeightingAdapter.cpp0000664016516101651610000001250513344612246023401 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::CentralRelativeWeightingAdapter::CentralRelativeWeightingAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const std::vector & weights ) : RelativeAdapterBase(), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _weights(weights) {} opengv::relative_pose::CentralRelativeWeightingAdapter::CentralRelativeWeightingAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const std::vector & weights, const rotation_t & R12 ) : RelativeAdapterBase(R12), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _weights(weights) {} opengv::relative_pose::CentralRelativeWeightingAdapter::CentralRelativeWeightingAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const std::vector & weights, const translation_t & t12, const rotation_t & R12 ) : RelativeAdapterBase(t12,R12), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _weights(weights) {} opengv::relative_pose::CentralRelativeWeightingAdapter::~CentralRelativeWeightingAdapter() {} opengv::bearingVector_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getBearingVector1( size_t index ) const { assert(index < _bearingVectors1.size()); return _bearingVectors1[index]; } opengv::bearingVector_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getBearingVector2( size_t index ) const { assert(index < _bearingVectors2.size()); return _bearingVectors2[index]; } double opengv::relative_pose::CentralRelativeWeightingAdapter:: getWeight( size_t index ) const { assert(index < _weights.size()); return _weights[index]; } opengv::translation_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getCamOffset1( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getCamRotation1( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Matrix3d::Identity(); } opengv::translation_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getCamOffset2( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getCamRotation2( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Matrix3d::Identity(); } size_t opengv::relative_pose::CentralRelativeWeightingAdapter:: getNumberCorrespondences() const { return _bearingVectors2.size(); } opengv/src/relative_pose/NoncentralRelativeMultiAdapter.cpp0000664016516101651610000001416313344612246023263 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::NoncentralRelativeMultiAdapter::NoncentralRelativeMultiAdapter( std::vector > bearingVectors1, std::vector > bearingVectors2, const translations_t & camOffsets, const rotations_t & camRotations ) : _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _camOffsets(camOffsets), _camRotations(camRotations) { // The following variables are needed for the serialization and // de-serialization of indices size_t singleIndexOffset = 0; for( size_t pairIndex = 0; pairIndex < bearingVectors2.size(); pairIndex++ ) { singleIndexOffsets.push_back(singleIndexOffset); for( size_t correspondenceIndex = 0; correspondenceIndex < bearingVectors2[pairIndex]->size(); correspondenceIndex++ ) { multiPairIndices.push_back(pairIndex); multiKeypointIndices.push_back(correspondenceIndex); } singleIndexOffset += bearingVectors2[pairIndex]->size(); } } opengv::relative_pose::NoncentralRelativeMultiAdapter::~NoncentralRelativeMultiAdapter() {} opengv::bearingVector_t opengv::relative_pose::NoncentralRelativeMultiAdapter:: getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const { assert(pairIndex < _bearingVectors1.size()); assert(correspondenceIndex < _bearingVectors1[pairIndex]->size()); return (*_bearingVectors1[pairIndex])[correspondenceIndex]; } opengv::bearingVector_t opengv::relative_pose::NoncentralRelativeMultiAdapter:: getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const { assert(pairIndex < _bearingVectors2.size()); assert(correspondenceIndex < _bearingVectors2[pairIndex]->size()); return (*_bearingVectors2[pairIndex])[correspondenceIndex]; } double opengv::relative_pose::NoncentralRelativeMultiAdapter:: getWeight( size_t pairIndex, size_t correspondenceIndex ) const { return 1.0; } opengv::translation_t opengv::relative_pose::NoncentralRelativeMultiAdapter:: getCamOffset( size_t pairIndex ) const { assert(pairIndex < _camOffsets.size()); return _camOffsets[pairIndex]; } opengv::rotation_t opengv::relative_pose::NoncentralRelativeMultiAdapter:: getCamRotation( size_t pairIndex ) const { assert(pairIndex < _camRotations.size()); return _camRotations[pairIndex]; } size_t opengv::relative_pose::NoncentralRelativeMultiAdapter:: getNumberCorrespondences(size_t pairIndex) const { assert(pairIndex < _bearingVectors2.size()); return _bearingVectors2[pairIndex]->size(); } size_t opengv::relative_pose::NoncentralRelativeMultiAdapter:: getNumberPairs() const { return _camOffsets.size(); } //important conversion between the serialized and the multi interface std::vector opengv::relative_pose::NoncentralRelativeMultiAdapter:: convertMultiIndices( const std::vector > & multiIndices ) const { std::vector singleIndices; for(size_t pairIndex = 0; pairIndex < multiIndices.size(); pairIndex++) { for( size_t correspondenceIndex = 0; correspondenceIndex < multiIndices[pairIndex].size(); correspondenceIndex++ ) { singleIndices.push_back(convertMultiIndex( pairIndex, multiIndices[pairIndex][correspondenceIndex] )); } } return singleIndices; } int opengv::relative_pose::NoncentralRelativeMultiAdapter:: convertMultiIndex( size_t pairIndex, size_t correspondenceIndex ) const { return singleIndexOffsets[pairIndex]+correspondenceIndex; } int opengv::relative_pose::NoncentralRelativeMultiAdapter:: multiPairIndex( size_t index ) const { return multiPairIndices[index]; } int opengv::relative_pose::NoncentralRelativeMultiAdapter:: multiCorrespondenceIndex( size_t index ) const { return multiKeypointIndices[index]; } opengv/src/relative_pose/NoncentralRelativeAdapter.cpp0000664016516101651610000001355713344612246022256 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::NoncentralRelativeAdapter::NoncentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const camCorrespondences_t & camCorrespondences1, const camCorrespondences_t & camCorrespondences2, const translations_t & camOffsets, const rotations_t & camRotations ) : RelativeAdapterBase(), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _camCorrespondences1(camCorrespondences1), _camCorrespondences2(camCorrespondences2), _camOffsets(camOffsets), _camRotations(camRotations) {} opengv::relative_pose::NoncentralRelativeAdapter::NoncentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const camCorrespondences_t & camCorrespondences1, const camCorrespondences_t & camCorrespondences2, const translations_t & camOffsets, const rotations_t & camRotations, const rotation_t & R12 ) : RelativeAdapterBase(R12), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _camCorrespondences1(camCorrespondences1), _camCorrespondences2(camCorrespondences2), _camOffsets(camOffsets), _camRotations(camRotations) {} opengv::relative_pose::NoncentralRelativeAdapter::NoncentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const camCorrespondences_t & camCorrespondences1, const camCorrespondences_t & camCorrespondences2, const translations_t & camOffsets, const rotations_t & camRotations, const translation_t & t12, const rotation_t & R12 ) : RelativeAdapterBase(t12,R12), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _camCorrespondences1(camCorrespondences1), _camCorrespondences2(camCorrespondences2), _camOffsets(camOffsets), _camRotations(camRotations) {} opengv::relative_pose::NoncentralRelativeAdapter::~NoncentralRelativeAdapter() {} opengv::bearingVector_t opengv::relative_pose::NoncentralRelativeAdapter:: getBearingVector1( size_t index ) const { assert(index < _bearingVectors1.size()); return _bearingVectors1[index]; } opengv::bearingVector_t opengv::relative_pose::NoncentralRelativeAdapter:: getBearingVector2( size_t index ) const { assert(index < _bearingVectors2.size()); return _bearingVectors2[index]; } double opengv::relative_pose::NoncentralRelativeAdapter:: getWeight( size_t index ) const { return 1.0; } opengv::translation_t opengv::relative_pose::NoncentralRelativeAdapter:: getCamOffset1( size_t index ) const { assert(_camCorrespondences1[index] < _camOffsets.size()); return _camOffsets[_camCorrespondences1[index]]; } opengv::rotation_t opengv::relative_pose::NoncentralRelativeAdapter:: getCamRotation1( size_t index ) const { assert(_camCorrespondences1[index] < _camRotations.size()); return _camRotations[_camCorrespondences1[index]]; } opengv::translation_t opengv::relative_pose::NoncentralRelativeAdapter:: getCamOffset2( size_t index ) const { assert(_camCorrespondences2[index] < _camOffsets.size()); return _camOffsets[_camCorrespondences2[index]]; } opengv::rotation_t opengv::relative_pose::NoncentralRelativeAdapter:: getCamRotation2( size_t index ) const { assert(_camCorrespondences2[index] < _camRotations.size()); return _camRotations[_camCorrespondences2[index]]; } size_t opengv::relative_pose::NoncentralRelativeAdapter:: getNumberCorrespondences() const { return _bearingVectors2.size(); } opengv/src/relative_pose/methods.cpp0000664016516101651610000010653313344612246016616 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include opengv::translation_t opengv::relative_pose::twopt( const RelativeAdapterBase & adapter, bool unrotate, const std::vector & indices ) { assert(indices.size()>1); return twopt( adapter, unrotate, indices[0], indices[1] ); }; opengv::translation_t opengv::relative_pose::twopt( const RelativeAdapterBase & adapter, bool unrotate, size_t index0, size_t index1 ) { bearingVector_t f1 = adapter.getBearingVector1(index0); bearingVector_t f1prime = adapter.getBearingVector2(index0); bearingVector_t f2 = adapter.getBearingVector1(index1); bearingVector_t f2prime = adapter.getBearingVector2(index1); if(unrotate) { rotation_t R12 = adapter.getR12(); f1prime = R12 * f1prime; f2prime = R12 * f2prime; } Eigen::Vector3d normal1 = f1.cross(f1prime); Eigen::Vector3d normal2 = f2.cross(f2prime); translation_t translation = normal1.cross(normal2); translation = translation/translation.norm(); Eigen::Vector3d opticalFlow = f1 - f1prime; if( opticalFlow.dot(translation) < 0 ) translation = -translation; return translation; }; opengv::rotation_t opengv::relative_pose::twopt_rotationOnly( const RelativeAdapterBase & adapter, const std::vector & indices ) { assert(indices.size() > 1); return twopt_rotationOnly( adapter, indices[0], indices[1] ); }; opengv::rotation_t opengv::relative_pose::twopt_rotationOnly( const RelativeAdapterBase & adapter, size_t index0, size_t index1) { Eigen::Vector3d pointsCenter1 = adapter.getBearingVector1(index0) + adapter.getBearingVector1(index1); Eigen::Vector3d pointsCenter2 = adapter.getBearingVector2(index0) + adapter.getBearingVector2(index1); pointsCenter1 = pointsCenter1/3.0; pointsCenter2 = pointsCenter2/3.0; Eigen::MatrixXd Hcross(3,3); Hcross = Eigen::Matrix3d::Zero(); Eigen::Vector3d f = adapter.getBearingVector1(index0) - pointsCenter1; Eigen::Vector3d fprime = adapter.getBearingVector2(index0) - pointsCenter2; Hcross += fprime * f.transpose(); f = adapter.getBearingVector1(index1) - pointsCenter1; fprime = adapter.getBearingVector2(index1) - pointsCenter2; Hcross += fprime * f.transpose(); return math::arun(Hcross); }; namespace opengv { namespace relative_pose { rotation_t rotationOnly( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 2); Eigen::Vector3d pointsCenter1 = Eigen::Vector3d::Zero(); Eigen::Vector3d pointsCenter2 = Eigen::Vector3d::Zero(); for( size_t i = 0; i < numberCorrespondences; i++ ) { pointsCenter1 += adapter.getBearingVector1(indices[i]); pointsCenter2 += adapter.getBearingVector2(indices[i]); } pointsCenter1 = pointsCenter1 / numberCorrespondences; pointsCenter2 = pointsCenter2 / numberCorrespondences; Eigen::MatrixXd Hcross(3,3); Hcross = Eigen::Matrix3d::Zero(); for( size_t i = 0; i < numberCorrespondences; i++ ) { Eigen::Vector3d f = adapter.getBearingVector1(indices[i]) - pointsCenter1; Eigen::Vector3d fprime = adapter.getBearingVector2(indices[i]) - pointsCenter2; Hcross += fprime * f.transpose(); } return math::arun(Hcross); }; } } opengv::rotation_t opengv::relative_pose::rotationOnly( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return rotationOnly(adapter,idx); }; opengv::rotation_t opengv::relative_pose::rotationOnly( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return rotationOnly(adapter,idx); }; namespace opengv { namespace relative_pose { complexEssentials_t fivept_stewenius( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 4); Eigen::MatrixXd Q(numberCorrespondences,9); for( size_t i = 0; i < numberCorrespondences; i++ ) { //bearingVector_t f = adapter.getBearingVector1(indices[i]); //bearingVector_t fprime = adapter.getBearingVector2(indices[i]); //Stewenius' algorithm is computing the inverse transformation, so we simply //invert the input here bearingVector_t f = adapter.getBearingVector2(indices[i]); bearingVector_t fprime = adapter.getBearingVector1(indices[i]); Eigen::Matrix row; row << f[0]*fprime[0], f[1]*fprime[0], f[2]*fprime[0], f[0]*fprime[1], f[1]*fprime[1], f[2]*fprime[1], f[0]*fprime[2], f[1]*fprime[2], f[2]*fprime[2]; Q.row(i) = row; } Eigen::JacobiSVD< Eigen::MatrixXd > SVD(Q, Eigen::ComputeFullV ); Eigen::Matrix EE = SVD.matrixV().block(0,5,9,4); complexEssentials_t complexEssentials; modules::fivept_stewenius_main(EE,complexEssentials); return complexEssentials; }; } } opengv::complexEssentials_t opengv::relative_pose::fivept_stewenius( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return fivept_stewenius(adapter,idx); }; opengv::complexEssentials_t opengv::relative_pose::fivept_stewenius( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return fivept_stewenius(adapter,idx); }; namespace opengv { namespace relative_pose { essentials_t fivept_nister( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 4); Eigen::MatrixXd Q(numberCorrespondences,9); for( size_t i = 0; i < numberCorrespondences; i++ ) { //bearingVector_t f = adapter.getBearingVector1(indices[i]); //bearingVector_t fprime = adapter.getBearingVector2(indices[i]); //Nister's algorithm is computing the inverse transformation, so we simply //invert the input here bearingVector_t f = adapter.getBearingVector2(indices[i]); bearingVector_t fprime = adapter.getBearingVector1(indices[i]); Eigen::Matrix row; row << f[0]*fprime[0], f[1]*fprime[0], f[2]*fprime[0], f[0]*fprime[1], f[1]*fprime[1], f[2]*fprime[1], f[0]*fprime[2], f[1]*fprime[2], f[2]*fprime[2]; Q.row(i) = row; } Eigen::JacobiSVD< Eigen::MatrixXd > SVD(Q, Eigen::ComputeFullV ); Eigen::Matrix EE = SVD.matrixV().block(0,5,9,4); essentials_t essentials; modules::fivept_nister_main(EE,essentials); return essentials; }; } } opengv::essentials_t opengv::relative_pose::fivept_nister( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return fivept_nister(adapter,idx); }; opengv::essentials_t opengv::relative_pose::fivept_nister( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return fivept_nister(adapter,idx); }; opengv::rotations_t opengv::relative_pose::fivept_kneip( const RelativeAdapterBase & adapter, const std::vector & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences == 5); Eigen::Matrix f1; Eigen::Matrix f2; for(size_t i = 0; i < numberCorrespondences; i++) { f1.col(i) = adapter.getBearingVector1(indices[i]); f2.col(i) = adapter.getBearingVector2(indices[i]); } rotations_t rotations; modules::fivept_kneip_main( f1, f2, rotations ); return rotations; } namespace opengv { namespace relative_pose { essentials_t sevenpt( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 6); Eigen::MatrixXd A(numberCorrespondences,9); for( size_t i = 0; i < numberCorrespondences; i++ ) { //bearingVector_t f1 = adapter.getBearingVector1(indices[i]); //bearingVector_t f2 = adapter.getBearingVector2(indices[i]); //The seven-point is computing the inverse transformation, which is why we //invert the input bearingVector_t f1 = adapter.getBearingVector2(indices[i]); bearingVector_t f2 = adapter.getBearingVector1(indices[i]); A.block<1,3>(i,0) = f2[0] * f1.transpose(); A.block<1,3>(i,3) = f2[1] * f1.transpose(); A.block<1,3>(i,6) = f2[2] * f1.transpose(); } Eigen::JacobiSVD< Eigen::MatrixXd > SVD( A, Eigen::ComputeFullU | Eigen::ComputeFullV ); Eigen::Matrix f1 = SVD.matrixV().col(8); Eigen::Matrix f2 = SVD.matrixV().col(7); Eigen::MatrixXd F1_temp(3,3); F1_temp.col(0) = f1.block<3,1>(0,0); F1_temp.col(1) = f1.block<3,1>(3,0); F1_temp.col(2) = f1.block<3,1>(6,0); essential_t F1 = F1_temp.transpose(); Eigen::MatrixXd F2_temp(3,3); F2_temp.col(0) = f2.block<3,1>(0,0); F2_temp.col(1) = f2.block<3,1>(3,0); F2_temp.col(2) = f2.block<3,1>(6,0); essential_t F2 = F2_temp.transpose(); double eps = 0.00000001; essentials_t essentials; if( fabs(F1.determinant()) < eps || numberCorrespondences > 7 ) { essentials.push_back(F1); } else { essential_t M = F2.inverse() * F1; Eigen::EigenSolver< essential_t > Eig(M,true); Eigen::Matrix< std::complex,3,1 > D = Eig.eigenvalues(); double val1 = fabs(D(0,0).imag()); double val2 = fabs(D(1,0).imag()); double val3 = fabs(D(2,0).imag()); if( val1 < eps && val2 < eps && val3 < eps ) { essentials.push_back( F1 - D(0,0).real() * F2 ); essentials.push_back( F1 - D(1,0).real() * F2 ); essentials.push_back( F1 - D(2,0).real() * F2 ); } else { double min = val1; int minIndex = 0; if( val2 < min ) { min = val2; minIndex = 1; } if( val3 < min ) minIndex = 2; essentials.push_back( F1 - D(minIndex,0).real() * F2 ); } } return essentials; } } } opengv::essentials_t opengv::relative_pose::sevenpt( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return sevenpt(adapter,idx); } opengv::essentials_t opengv::relative_pose::sevenpt( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return sevenpt(adapter,idx); } namespace opengv { namespace relative_pose { essential_t eightpt( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 7); Eigen::MatrixXd A(numberCorrespondences,9); for( size_t i = 0; i < numberCorrespondences; i++ ) { //bearingVector_t f1 = adapter.getBearingVector1(indices[i]); //bearingVector_t f2 = adapter.getBearingVector2(indices[i]); //The eight-point essentially computes the inverse transformation, which is //why we invert the input here bearingVector_t f1 = adapter.getBearingVector2(indices[i]); bearingVector_t f2 = adapter.getBearingVector1(indices[i]); A.block<1,3>(i,0) = f2[0] * f1.transpose(); A.block<1,3>(i,3) = f2[1] * f1.transpose(); A.block<1,3>(i,6) = f2[2] * f1.transpose(); } Eigen::JacobiSVD< Eigen::MatrixXd > SVD( A, Eigen::ComputeFullU | Eigen::ComputeFullV ); Eigen::Matrix f = SVD.matrixV().col(8); Eigen::MatrixXd F_temp(3,3); F_temp.col(0) = f.block<3,1>(0,0); F_temp.col(1) = f.block<3,1>(3,0); F_temp.col(2) = f.block<3,1>(6,0); essential_t F = F_temp.transpose(); Eigen::JacobiSVD< Eigen::MatrixXd > SVD2( F, Eigen::ComputeFullU | Eigen::ComputeFullV ); Eigen::Matrix3d S = Eigen::Matrix3d::Zero(); S(0,0) = SVD2.singularValues()[0]; S(1,1) = SVD2.singularValues()[1]; Eigen::Matrix3d U = SVD2.matrixU(); Eigen::Matrix3d Vtr = SVD2.matrixV().transpose(); essential_t essential = U * S * Vtr; return essential; } } } opengv::essential_t opengv::relative_pose::eightpt( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return eightpt(adapter,idx); } opengv::essential_t opengv::relative_pose::eightpt( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return eightpt(adapter,idx); } namespace opengv { namespace relative_pose { rotation_t eigensolver( const RelativeAdapterBase & adapter, const Indices & indices, eigensolverOutput_t & output, bool useWeights ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 4); Eigen::Matrix3d xxF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d yyF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d zzF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d xyF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d yzF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d zxF = Eigen::Matrix3d::Zero(); //compute the norm of all the scores double norm = 0.0; for(size_t i=0; i < numberCorrespondences; i++) norm += pow(adapter.getWeight(indices[i]),2); norm = sqrt(norm); //Fill summation terms for(size_t i=0; i < numberCorrespondences; i++) { bearingVector_t f1 = adapter.getBearingVector1(indices[i]); bearingVector_t f2 = adapter.getBearingVector2(indices[i]); Eigen::Matrix3d F = f2*f2.transpose(); double weight = 1.0; if( useWeights ) weight = adapter.getWeight(indices[i])/norm; xxF = xxF + weight*f1[0]*f1[0]*F; yyF = yyF + weight*f1[1]*f1[1]*F; zzF = zzF + weight*f1[2]*f1[2]*F; xyF = xyF + weight*f1[0]*f1[1]*F; yzF = yzF + weight*f1[1]*f1[2]*F; zxF = zxF + weight*f1[2]*f1[0]*F; } //Do minimization modules::eigensolver_main(xxF,yyF,zzF,xyF,yzF,zxF,output); //Correct the translation bearingVector_t f1 = adapter.getBearingVector1(indices[0]); bearingVector_t f2 = adapter.getBearingVector2(indices[0]); f2 = output.rotation * f2; Eigen::Vector3d opticalFlow = f1 - f2; if( opticalFlow.dot(output.translation) < 0.0 ) output.translation = -output.translation; return output.rotation; } } } opengv::rotation_t opengv::relative_pose::eigensolver( const RelativeAdapterBase & adapter, eigensolverOutput_t & output, bool useWeights ) { Indices idx(adapter.getNumberCorrespondences()); return eigensolver(adapter,idx,output,useWeights); } opengv::rotation_t opengv::relative_pose::eigensolver( const RelativeAdapterBase & adapter, const std::vector & indices, eigensolverOutput_t & output, bool useWeights ) { Indices idx(indices); return eigensolver(adapter,idx,output,useWeights); } opengv::rotation_t opengv::relative_pose::eigensolver( const RelativeAdapterBase & adapter, bool useWeights ) { eigensolverOutput_t output; output.rotation = adapter.getR12(); return eigensolver(adapter,output,useWeights); } opengv::rotation_t opengv::relative_pose::eigensolver( const RelativeAdapterBase & adapter, const std::vector & indices, bool useWeights ) { eigensolverOutput_t output; output.rotation = adapter.getR12(); return eigensolver(adapter,indices,output,useWeights); } namespace opengv { namespace relative_pose { rotations_t sixpt( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences == 6); Eigen::Matrix L1; Eigen::Matrix L2; for(size_t i = 0; i < numberCorrespondences; i++) { bearingVector_t f1 = adapter.getCamRotation1(indices[i]) * adapter.getBearingVector1(indices[i]); bearingVector_t f2 = adapter.getCamRotation2(indices[i]) * adapter.getBearingVector2(indices[i]); L1.block<3,1>(0,i) = f1; L2.block<3,1>(0,i) = f2; L1.block<3,1>(3,i) = f1.cross(adapter.getCamOffset1(indices[i])); L2.block<3,1>(3,i) = f2.cross(adapter.getCamOffset2(indices[i])); } rotations_t solutions; modules::sixpt_main( L1, L2, solutions ); return solutions; } } } opengv::rotations_t opengv::relative_pose::sixpt( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return sixpt(adapter,idx); } opengv::rotations_t opengv::relative_pose::sixpt( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return sixpt(adapter,idx); } namespace opengv { namespace relative_pose { rotation_t ge( const RelativeAdapterBase & adapter, const Indices & indices, geOutput_t & output, bool useWeights ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 5); Eigen::Matrix3d xxF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d yyF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d zzF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d xyF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d yzF = Eigen::Matrix3d::Zero(); Eigen::Matrix3d zxF = Eigen::Matrix3d::Zero(); Eigen::Matrix x1P = Eigen::Matrix::Zero(); Eigen::Matrix y1P = Eigen::Matrix::Zero(); Eigen::Matrix z1P = Eigen::Matrix::Zero(); Eigen::Matrix x2P = Eigen::Matrix::Zero(); Eigen::Matrix y2P = Eigen::Matrix::Zero(); Eigen::Matrix z2P = Eigen::Matrix::Zero(); Eigen::Matrix m11P = Eigen::Matrix::Zero(); Eigen::Matrix m12P = Eigen::Matrix::Zero(); Eigen::Matrix m22P = Eigen::Matrix::Zero(); //compute the norm of all the scores double norm = 0.0; for(size_t i=0; i < numberCorrespondences; i++) norm += pow(adapter.getWeight(indices[i]),2); norm = sqrt(norm); //Fill summation terms for(size_t i=0; i < numberCorrespondences; i++) { //get the weight of this feature double weight = 1.0; if( useWeights ) weight = adapter.getWeight(indices[i])/norm; //unrotate the bearing vectors bearingVector_t f1 = adapter.getCamRotation1(indices[i]) * adapter.getBearingVector1(indices[i]); bearingVector_t f2 = adapter.getCamRotation2(indices[i]) * adapter.getBearingVector2(indices[i]); //compute the standard summation terms Eigen::Matrix3d F = f2*f2.transpose(); xxF = xxF + weight*f1[0]*f1[0]*F; yyF = yyF + weight*f1[1]*f1[1]*F; zzF = zzF + weight*f1[2]*f1[2]*F; xyF = xyF + weight*f1[0]*f1[1]*F; yzF = yzF + weight*f1[1]*f1[2]*F; zxF = zxF + weight*f1[2]*f1[0]*F; //now compute the "cross"-summation terms Eigen::Vector3d t1 = adapter.getCamOffset1(indices[i]); Eigen::Vector3d t2 = adapter.getCamOffset2(indices[i]); Eigen::Matrix f2_19; double temp = f1[1]*t1[2]-f1[2]*t1[1]; f2_19(0,0) = f2[0] * temp; f2_19(0,1) = f2[1] * temp; f2_19(0,2) = f2[2] * temp; temp = f1[2]*t1[0]-f1[0]*t1[2]; f2_19(0,3) = f2[0] * temp; f2_19(0,4) = f2[1] * temp; f2_19(0,5) = f2[2] * temp; temp = f1[0]*t1[1]-f1[1]*t1[0]; f2_19(0,6) = f2[0] * temp; f2_19(0,7) = f2[1] * temp; f2_19(0,8) = f2[2] * temp; Eigen::Matrix f1_19; temp = f2[1]*t2[2]-f2[2]*t2[1]; f1_19(0,0) = f1[0] * temp; f1_19(0,1) = f1[1] * temp; f1_19(0,2) = f1[2] * temp; temp = f2[2]*t2[0]-f2[0]*t2[2]; f1_19(0,3) = f1[0] * temp; f1_19(0,4) = f1[1] * temp; f1_19(0,5) = f1[2] * temp; temp = f2[0]*t2[1]-f2[1]*t2[0]; f1_19(0,6) = f1[0] * temp; f1_19(0,7) = f1[1] * temp; f1_19(0,8) = f1[2] * temp; if( useWeights ) { x1P = x1P + ( (weight * f1[0]) * f2 ) * f1_19; y1P = y1P + ( (weight * f1[1]) * f2 ) * f1_19; z1P = z1P + ( (weight * f1[2]) * f2 ) * f1_19; x2P = x2P + ( (weight * f1[0]) * f2 ) * f2_19; y2P = y2P + ( (weight * f1[1]) * f2 ) * f2_19; z2P = z2P + ( (weight * f1[2]) * f2 ) * f2_19; m11P = m11P - ( weight * f1_19.transpose() ) * f1_19; m22P = m22P - ( weight * f2_19.transpose() ) * f2_19; m12P = m12P - ( weight * f2_19.transpose() ) * f1_19; } else { x1P = x1P + ( f1[0] * f2 ) * f1_19; y1P = y1P + ( f1[1] * f2 ) * f1_19; z1P = z1P + ( f1[2] * f2 ) * f1_19; x2P = x2P + ( f1[0]) * f2 * f2_19; y2P = y2P + ( f1[1]) * f2 * f2_19; z2P = z2P + ( f1[2]) * f2 * f2_19; m11P = m11P - f1_19.transpose() * f1_19; m22P = m22P - f2_19.transpose() * f2_19; m12P = m12P - f2_19.transpose() * f1_19; } } Eigen::Vector3d pointsCenter1 = Eigen::Vector3d::Zero(); Eigen::Vector3d pointsCenter2 = Eigen::Vector3d::Zero(); for( size_t i = 0; i < numberCorrespondences; i++ ) { pointsCenter1 += adapter.getCamRotation1(indices[i]) * adapter.getBearingVector1(indices[i]); pointsCenter2 += adapter.getCamRotation2(indices[i]) * adapter.getBearingVector2(indices[i]); } pointsCenter1 = pointsCenter1 / numberCorrespondences; pointsCenter2 = pointsCenter2 / numberCorrespondences; Eigen::MatrixXd Hcross(3,3); Hcross = Eigen::Matrix3d::Zero(); for( size_t i = 0; i < numberCorrespondences; i++ ) { Eigen::Vector3d f = adapter.getCamRotation1(indices[i]) * adapter.getBearingVector1(indices[i]) - pointsCenter1; Eigen::Vector3d fprime = adapter.getCamRotation2(indices[i]) * adapter.getBearingVector2(indices[i]) - pointsCenter2; Hcross += fprime * f.transpose(); } rotation_t startingRotation = math::arun(Hcross); //Do minimization modules::ge_main2( xxF, yyF, zzF, xyF, yzF, zxF, x1P, y1P, z1P, x2P, y2P, z2P, m11P, m12P, m22P, math::rot2cayley(startingRotation), output); return output.rotation; } } } opengv::rotation_t opengv::relative_pose::ge( const RelativeAdapterBase & adapter, geOutput_t & output, bool useWeights ) { Indices idx(adapter.getNumberCorrespondences()); return ge(adapter,idx,output,useWeights); } opengv::rotation_t opengv::relative_pose::ge( const RelativeAdapterBase & adapter, const std::vector & indices, geOutput_t & output, bool useWeights ) { Indices idx(indices); return ge(adapter,idx,output,useWeights); } opengv::rotation_t opengv::relative_pose::ge( const RelativeAdapterBase & adapter, bool useWeights ) { geOutput_t output; //output.rotation = adapter.getR12(); //finding starting value using arun return ge(adapter,output,useWeights); } opengv::rotation_t opengv::relative_pose::ge( const RelativeAdapterBase & adapter, const std::vector & indices, bool useWeights ) { geOutput_t output; //output.rotation = adapter.getR12(); //finding starting value using arun return ge(adapter,indices,output,useWeights); } namespace opengv { namespace relative_pose { transformation_t seventeenpt( const RelativeAdapterBase & adapter, const Indices & indices ) { size_t numberCorrespondences = indices.size(); assert(numberCorrespondences > 16); Eigen::MatrixXd AE(numberCorrespondences,9); Eigen::MatrixXd AR(numberCorrespondences,9); for( size_t i = 0; i < numberCorrespondences; i++ ) { bearingVector_t d1 = adapter.getBearingVector1(indices[i]); bearingVector_t d2 = adapter.getBearingVector2(indices[i]); translation_t v1 = adapter.getCamOffset1(indices[i]); translation_t v2 = adapter.getCamOffset2(indices[i]); rotation_t R1 = adapter.getCamRotation1(indices[i]); rotation_t R2 = adapter.getCamRotation2(indices[i]); //unrotate the bearing-vectors to express everything in the body frame d1 = R1*d1; d2 = R2*d2; //generate the Plücker line coordinates Eigen::Matrix l1; l1.block<3,1>(0,0) = d1; l1.block<3,1>(3,0) = v1.cross(d1); Eigen::Matrix l2; l2.block<3,1>(0,0) = d2; l2.block<3,1>(3,0) = v2.cross(d2); //fill line of matrix A AE(i,0) = l2[0]*l1[0]; AE(i,1) = l2[0]*l1[1]; AE(i,2) = l2[0]*l1[2]; AE(i,3) = l2[1]*l1[0]; AE(i,4) = l2[1]*l1[1]; AE(i,5) = l2[1]*l1[2]; AE(i,6) = l2[2]*l1[0]; AE(i,7) = l2[2]*l1[1]; AE(i,8) = l2[2]*l1[2]; AR(i,0) = l2[0]*l1[3]+l2[3]*l1[0]; AR(i,1) = l2[0]*l1[4]+l2[3]*l1[1]; AR(i,2) = l2[0]*l1[5]+l2[3]*l1[2]; AR(i,3) = l2[1]*l1[3]+l2[4]*l1[0]; AR(i,4) = l2[1]*l1[4]+l2[4]*l1[1]; AR(i,5) = l2[1]*l1[5]+l2[4]*l1[2]; AR(i,6) = l2[2]*l1[3]+l2[5]*l1[0]; AR(i,7) = l2[2]*l1[4]+l2[5]*l1[1]; AR(i,8) = l2[2]*l1[5]+l2[5]*l1[2]; } Eigen::JacobiSVD< Eigen::MatrixXd > SVDARP( AR, Eigen::ComputeThinU | Eigen::ComputeThinV ); Eigen::VectorXd sigma_ = SVDARP.singularValues(); double pinvtoler_ = sigma_(0)*numberCorrespondences*NumTraits::epsilon(); Eigen::MatrixXd SigmaInverse_(9,9); SigmaInverse_ = Eigen::MatrixXd::Zero(9,9); for ( size_t i=0; i < 9; ++i) { double temp = sigma_(i); if( temp > pinvtoler_ ) SigmaInverse_(i,i) = 1.0/temp; } Eigen::MatrixXd ARP(9,numberCorrespondences); ARP = SVDARP.matrixV()*SigmaInverse_*SVDARP.matrixU().transpose(); Eigen::MatrixXd B(numberCorrespondences,numberCorrespondences); B = -Eigen::MatrixXd::Identity(numberCorrespondences,numberCorrespondences); B = B + AR*ARP; Eigen::MatrixXd C = B*AE; Eigen::JacobiSVD< Eigen::MatrixXd > SVDE( C, Eigen::ComputeThinU | Eigen::ComputeThinV ); Eigen::Matrix e = SVDE.matrixV().col(8); Eigen::MatrixXd E_temp(3,3); E_temp.col(0) = e.block<3,1>(0,0); E_temp.col(1) = e.block<3,1>(3,0); E_temp.col(2) = e.block<3,1>(6,0); essential_t E = E_temp.transpose(); Eigen::JacobiSVD< Eigen::MatrixXd > SVDR( E, Eigen::ComputeFullV | Eigen::ComputeFullU ); Eigen::Matrix3d W = Eigen::Matrix3d::Zero(); W(0,1) = -1.0; W(1,0) = 1.0; W(2,2) = 1.0; // get possible rotation and translation vectors rotation_t Ra = SVDR.matrixU() * W * SVDR.matrixV().transpose(); rotation_t Rb = SVDR.matrixU() * W.transpose() * SVDR.matrixV().transpose(); // change sign if det = -1 if( Ra.determinant() < 0 ) Ra = -Ra; if( Rb.determinant() < 0 ) Rb = -Rb; Ra.transposeInPlace(); Rb.transposeInPlace(); Eigen::MatrixXd A_tra(numberCorrespondences,3); Eigen::MatrixXd A_trb(numberCorrespondences,3); Eigen::VectorXd b_tra(numberCorrespondences); Eigen::VectorXd b_trb(numberCorrespondences); for( size_t i = 0; i < numberCorrespondences; i++ ) { bearingVector_t d1 = adapter.getBearingVector1(indices[i]); bearingVector_t d2 = adapter.getBearingVector2(indices[i]); translation_t v1 = adapter.getCamOffset1(indices[i]); translation_t v2 = adapter.getCamOffset2(indices[i]); rotation_t R1 = adapter.getCamRotation1(indices[i]); rotation_t R2 = adapter.getCamRotation2(indices[i]); //unrotate the bearing-vectors to express everything in the body frame d1 = R1*d1; d2 = R2*d2; A_tra(i,0) = d1[2]*d2[0]*Ra(1,0)+d1[2]*d2[1]*Ra(1,1)+d1[2]*d2[2]*Ra(1,2) -d1[1]*d2[0]*Ra(2,0)-d1[1]*d2[1]*Ra(2,1)-d1[1]*d2[2]*Ra(2,2); A_tra(i,1) = d1[0]*d2[0]*Ra(2,0)+d1[0]*d2[1]*Ra(2,1)+d1[0]*d2[2]*Ra(2,2) -d1[2]*d2[0]*Ra(0,0)-d1[2]*d2[1]*Ra(0,1)-d1[2]*d2[2]*Ra(0,2); A_tra(i,2) = d1[1]*d2[0]*Ra(0,0)+d1[1]*d2[1]*Ra(0,1)+d1[1]*d2[2]*Ra(0,2) -d1[0]*d2[0]*Ra(1,0)-d1[0]*d2[1]*Ra(1,1)-d1[0]*d2[2]*Ra(1,2); A_trb(i,0) = d1[2]*d2[0]*Rb(1,0)+d1[2]*d2[1]*Rb(1,1)+d1[2]*d2[2]*Rb(1,2) -d1[1]*d2[0]*Rb(2,0)-d1[1]*d2[1]*Rb(2,1)-d1[1]*d2[2]*Rb(2,2); A_trb(i,1) = d1[0]*d2[0]*Rb(2,0)+d1[0]*d2[1]*Rb(2,1)+d1[0]*d2[2]*Rb(2,2) -d1[2]*d2[0]*Rb(0,0)-d1[2]*d2[1]*Rb(0,1)-d1[2]*d2[2]*Rb(0,2); A_trb(i,2) = d1[1]*d2[0]*Rb(0,0)+d1[1]*d2[1]*Rb(0,1)+d1[1]*d2[2]*Rb(0,2) -d1[0]*d2[0]*Rb(1,0)-d1[0]*d2[1]*Rb(1,1)-d1[0]*d2[2]*Rb(1,2); Eigen::Vector3d temp1 = v1.cross(d1); Eigen::Vector3d temp2 = v2.cross(d2); b_tra(i) = -d1.dot(Ra*temp2) -temp1.dot(Ra*d2); b_trb(i) = -d1.dot(Rb*temp2) -temp1.dot(Rb*d2); } Eigen::JacobiSVD< Eigen::MatrixXd > SVDa( A_tra, Eigen::ComputeThinU | Eigen::ComputeThinV ); Eigen::VectorXd sigma = SVDa.singularValues(); double pinvtoler = numberCorrespondences*sigma(0)*NumTraits::epsilon(); Eigen::MatrixXd SigmaInverse(3,3); SigmaInverse = Eigen::MatrixXd::Zero(3,3); for ( size_t i=0; i < 3; ++i) { double temp = sigma(i); if( temp > pinvtoler ) SigmaInverse(i,i) = 1.0/temp; } Eigen::MatrixXd PI(3,numberCorrespondences); PI = SVDa.matrixV()*SigmaInverse*SVDa.matrixU().transpose(); Eigen::Vector3d ta = PI*b_tra; Eigen::JacobiSVD< Eigen::MatrixXd > SVDb( A_trb, Eigen::ComputeThinU | Eigen::ComputeThinV ); sigma = SVDb.singularValues(); pinvtoler = numberCorrespondences*sigma(0)*NumTraits::epsilon(); SigmaInverse = Eigen::MatrixXd::Zero(3,3); for ( size_t i=0; i < 3; ++i) { double temp = sigma(i); if( temp > pinvtoler ) SigmaInverse(i,i) = 1.0/temp; } PI = SVDb.matrixV()*SigmaInverse*SVDb.matrixU().transpose(); Eigen::Vector3d tb = PI*b_trb; Eigen::VectorXd fita = A_tra * ta - b_tra; Eigen::VectorXd fitb = A_trb * tb - b_trb; transformation_t transformation; if( fita.norm() < fitb.norm() ) { transformation.block<3,3>(0,0) = Ra; transformation.col(3) = ta; } else { transformation.block<3,3>(0,0) = Rb; transformation.col(3) = tb; } return transformation; } } } opengv::transformation_t opengv::relative_pose::seventeenpt( const RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return seventeenpt(adapter,idx); } opengv::transformation_t opengv::relative_pose::seventeenpt( const RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return seventeenpt(adapter,idx); } namespace opengv { namespace relative_pose { struct OptimizeNonlinearFunctor1 : OptimizationFunctor { RelativeAdapterBase & _adapter; const Indices & _indices; OptimizeNonlinearFunctor1( RelativeAdapterBase & adapter, const Indices & indices ) : OptimizationFunctor(6,indices.size()), _adapter(adapter), _indices(indices) {} int operator()(const VectorXd &x, VectorXd &fvec) const { assert( x.size() == 6 ); assert( (unsigned int) fvec.size() == _indices.size()); //compute the current position translation_t translation = x.block<3,1>(0,0); cayley_t cayley = x.block<3,1>(3,0); rotation_t rotation = math::cayley2rot(cayley); Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < _indices.size(); i++ ) { translation_t cam1Offset = _adapter.getCamOffset1(_indices[i]); rotation_t cam1Rotation = _adapter.getCamRotation1(_indices[i]); translation_t cam2Offset = _adapter.getCamOffset2(_indices[i]); rotation_t cam2Rotation = _adapter.getCamRotation2(_indices[i]); translation_t directTranslation = cam1Rotation.transpose() * ((translation - cam1Offset) + rotation * cam2Offset); rotation_t directRotation = cam1Rotation.transpose() * rotation * cam2Rotation; _adapter.sett12(directTranslation); _adapter.setR12(directRotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = directRotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*directTranslation; p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,_indices[i]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(_indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(_indices[i]); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); double factor = 1.0; fvec[i] = factor*(reprojError1 + reprojError2); } return 0; } }; transformation_t optimize_nonlinear( RelativeAdapterBase & adapter, const Indices & indices ) { const int n=6; VectorXd x(n); x.block<3,1>(0,0) = adapter.gett12(); x.block<3,1>(3,0) = math::rot2cayley(adapter.getR12()); OptimizeNonlinearFunctor1 functor( adapter, indices ); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 1.E1*NumTraits::epsilon(); lm.parameters.xtol = 1.E1*NumTraits::epsilon(); lm.parameters.maxfev = 1000; lm.minimize(x); transformation_t transformation; transformation.col(3) = x.block<3,1>(0,0); transformation.block<3,3>(0,0) = math::cayley2rot(x.block<3,1>(3,0)); return transformation; } } } opengv::transformation_t opengv::relative_pose::optimize_nonlinear( RelativeAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return optimize_nonlinear(adapter,idx); } opengv::transformation_t opengv::relative_pose::optimize_nonlinear( RelativeAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return optimize_nonlinear(adapter,idx); } opengv/src/relative_pose/MANoncentralRelativeMulti.cpp0000664016516101651610000001515213344612246022177 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::MANoncentralRelativeMulti::MANoncentralRelativeMulti( const std::vector & bearingVectors1, const std::vector & bearingVectors2, const double * camOffsets, const std::vector & numberBearingVectors ) : _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _camOffsets(camOffsets), _numberBearingVectors(numberBearingVectors) { // The following variables are needed for the serialization and // de-serialization of indices size_t singleIndexOffset = 0; for( size_t pairIndex = 0; pairIndex < _numberBearingVectors.size(); pairIndex++ ) { singleIndexOffsets.push_back(singleIndexOffset); for( size_t correspondenceIndex = 0; correspondenceIndex < (unsigned int) _numberBearingVectors[pairIndex]; correspondenceIndex++ ) { multiPairIndices.push_back(pairIndex); multiKeypointIndices.push_back(correspondenceIndex); } singleIndexOffset += _numberBearingVectors[pairIndex]; } } opengv::relative_pose::MANoncentralRelativeMulti::~MANoncentralRelativeMulti() {} opengv::bearingVector_t opengv::relative_pose::MANoncentralRelativeMulti:: getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const { assert(pairIndex < _numberBearingVectors.size()); assert(correspondenceIndex < _numberBearingVectors[pairIndex]); bearingVector_t bearingVector; bearingVector[0] = _bearingVectors1[pairIndex][correspondenceIndex * 3]; bearingVector[1] = _bearingVectors1[pairIndex][correspondenceIndex * 3 + 1]; bearingVector[2] = _bearingVectors1[pairIndex][correspondenceIndex * 3 + 2]; return bearingVector; } opengv::bearingVector_t opengv::relative_pose::MANoncentralRelativeMulti:: getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const { assert(pairIndex < _numberBearingVectors.size()); assert(correspondenceIndex < _numberBearingVectors[pairIndex]); bearingVector_t bearingVector; bearingVector[0] = _bearingVectors2[pairIndex][correspondenceIndex * 3]; bearingVector[1] = _bearingVectors2[pairIndex][correspondenceIndex * 3 + 1]; bearingVector[2] = _bearingVectors2[pairIndex][correspondenceIndex * 3 + 2]; return bearingVector; } double opengv::relative_pose::MANoncentralRelativeMulti:: getWeight( size_t pairIndex, size_t correspondenceIndex ) const { return 1.0; } opengv::translation_t opengv::relative_pose::MANoncentralRelativeMulti:: getCamOffset( size_t pairIndex ) const { assert(pairIndex < _numberBearingVectors.size()); translation_t camOffset; camOffset[0] = _camOffsets[pairIndex * 3]; camOffset[1] = _camOffsets[pairIndex * 3 + 1]; camOffset[2] = _camOffsets[pairIndex * 3 + 2]; return camOffset; } opengv::rotation_t opengv::relative_pose::MANoncentralRelativeMulti:: getCamRotation( size_t pairIndex ) const { return Eigen::Matrix3d::Identity(); } size_t opengv::relative_pose::MANoncentralRelativeMulti:: getNumberCorrespondences(size_t pairIndex) const { assert(pairIndex < _numberBearingVectors.size()); return _numberBearingVectors[pairIndex]; } size_t opengv::relative_pose::MANoncentralRelativeMulti:: getNumberPairs() const { return _numberBearingVectors.size(); } //important conversion between the serialized and the multi interface std::vector opengv::relative_pose::MANoncentralRelativeMulti:: convertMultiIndices( const std::vector > & multiIndices ) const { std::vector singleIndices; for(size_t pairIndex = 0; pairIndex < multiIndices.size(); pairIndex++) { for( size_t correspondenceIndex = 0; correspondenceIndex < multiIndices[pairIndex].size(); correspondenceIndex++ ) singleIndices.push_back(convertMultiIndex( pairIndex, multiIndices[pairIndex][correspondenceIndex] )); } return singleIndices; } int opengv::relative_pose::MANoncentralRelativeMulti:: convertMultiIndex( size_t pairIndex, size_t correspondenceIndex ) const { return singleIndexOffsets[pairIndex]+correspondenceIndex; } int opengv::relative_pose::MANoncentralRelativeMulti:: multiPairIndex( size_t index ) const { return multiPairIndices[index]; } int opengv::relative_pose::MANoncentralRelativeMulti:: multiCorrespondenceIndex( size_t index ) const { return multiKeypointIndices[index]; } opengv/src/relative_pose/MACentralRelative.cpp0000664016516101651610000001132513344612246020447 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::MACentralRelative::MACentralRelative( const double * bearingVectors1, const double * bearingVectors2, int numberBearingVectors1, int numberBearingVectors2 ) : _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _numberBearingVectors1(numberBearingVectors1), _numberBearingVectors2(numberBearingVectors2) {} opengv::relative_pose::MACentralRelative::~MACentralRelative() {} opengv::bearingVector_t opengv::relative_pose::MACentralRelative:: getBearingVector1( size_t index ) const { bearingVector_t bearingVector; assert(index < _numberBearingVectors1); bearingVector[0] = _bearingVectors1[index * 3]; bearingVector[1] = _bearingVectors1[index * 3 + 1]; bearingVector[2] = _bearingVectors1[index * 3 + 2]; return bearingVector; } opengv::bearingVector_t opengv::relative_pose::MACentralRelative:: getBearingVector2( size_t index ) const { assert(index < _numberBearingVectors2); bearingVector_t bearingVector; bearingVector[0] = _bearingVectors2[index * 3]; bearingVector[1] = _bearingVectors2[index * 3 + 1]; bearingVector[2] = _bearingVectors2[index * 3 + 2]; return bearingVector; } double opengv::relative_pose::MACentralRelative:: getWeight( size_t index ) const { return 1.0; } opengv::translation_t opengv::relative_pose::MACentralRelative:: getCamOffset1( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::MACentralRelative:: getCamRotation1( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Matrix3d::Identity(); } opengv::translation_t opengv::relative_pose::MACentralRelative:: getCamOffset2( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::MACentralRelative:: getCamRotation2( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Matrix3d::Identity(); } size_t opengv::relative_pose::MACentralRelative:: getNumberCorrespondences() const { return _numberBearingVectors2; } opengv/src/relative_pose/CentralRelativeAdapter.cpp0000664016516101651610000001167513344612246021542 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::CentralRelativeAdapter::CentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2 ) : RelativeAdapterBase(), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2) {} opengv::relative_pose::CentralRelativeAdapter::CentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const rotation_t & R12 ) : RelativeAdapterBase(R12), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2) {} opengv::relative_pose::CentralRelativeAdapter::CentralRelativeAdapter( const bearingVectors_t & bearingVectors1, const bearingVectors_t & bearingVectors2, const translation_t & t12, const rotation_t & R12 ) : RelativeAdapterBase(t12,R12), _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2) {} opengv::relative_pose::CentralRelativeAdapter::~CentralRelativeAdapter() {} opengv::bearingVector_t opengv::relative_pose::CentralRelativeAdapter:: getBearingVector1( size_t index ) const { assert(index < _bearingVectors1.size()); return _bearingVectors1[index]; } opengv::bearingVector_t opengv::relative_pose::CentralRelativeAdapter:: getBearingVector2( size_t index ) const { assert(index < _bearingVectors2.size()); return _bearingVectors2[index]; } double opengv::relative_pose::CentralRelativeAdapter:: getWeight( size_t index ) const { return 1.0; } opengv::translation_t opengv::relative_pose::CentralRelativeAdapter:: getCamOffset1( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::CentralRelativeAdapter:: getCamRotation1( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Matrix3d::Identity(); } opengv::translation_t opengv::relative_pose::CentralRelativeAdapter:: getCamOffset2( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::CentralRelativeAdapter:: getCamRotation2( size_t index ) const { //We could also check here for camIndex being 0, because this adapter is made //for a single camera only return Eigen::Matrix3d::Identity(); } size_t opengv::relative_pose::CentralRelativeAdapter:: getNumberCorrespondences() const { return _bearingVectors2.size(); } opengv/src/relative_pose/MANoncentralRelative.cpp0000664016516101651610000001136013344612246021161 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::MANoncentralRelative::MANoncentralRelative( const double * bearingVectors1, const double * bearingVectors2, int numberBearingVectors1, int numberBearingVectors2 ) : _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2), _numberBearingVectors1(numberBearingVectors1), _numberBearingVectors2(numberBearingVectors2) {} opengv::relative_pose::MANoncentralRelative::~MANoncentralRelative() {} opengv::bearingVector_t opengv::relative_pose::MANoncentralRelative:: getBearingVector1( size_t index ) const { bearingVector_t bearingVector; assert(index < _numberBearingVectors1); bearingVector[0] = _bearingVectors1[index * 6]; bearingVector[1] = _bearingVectors1[index * 6 + 1]; bearingVector[2] = _bearingVectors1[index * 6 + 2]; return bearingVector; } opengv::bearingVector_t opengv::relative_pose::MANoncentralRelative:: getBearingVector2( size_t index ) const { assert(index < _numberBearingVectors2); bearingVector_t bearingVector; bearingVector[0] = _bearingVectors2[index * 6]; bearingVector[1] = _bearingVectors2[index * 6 + 1]; bearingVector[2] = _bearingVectors2[index * 6 + 2]; return bearingVector; } double opengv::relative_pose::MANoncentralRelative:: getWeight( size_t index ) const { return 1.0; } opengv::translation_t opengv::relative_pose::MANoncentralRelative:: getCamOffset1( size_t index ) const { translation_t camOffset; assert(index < _numberBearingVectors1); camOffset[0] = _bearingVectors1[index * 6 + 3]; camOffset[1] = _bearingVectors1[index * 6 + 4]; camOffset[2] = _bearingVectors1[index * 6 + 5]; return camOffset; } opengv::rotation_t opengv::relative_pose::MANoncentralRelative:: getCamRotation1( size_t index ) const { return Eigen::Matrix3d::Identity(); } opengv::translation_t opengv::relative_pose::MANoncentralRelative:: getCamOffset2( size_t index ) const { assert(index < _numberBearingVectors2); translation_t camOffset; camOffset[0] = _bearingVectors2[index * 6 + 3]; camOffset[1] = _bearingVectors2[index * 6 + 4]; camOffset[2] = _bearingVectors2[index * 6 + 5]; return camOffset; } opengv::rotation_t opengv::relative_pose::MANoncentralRelative:: getCamRotation2( size_t index ) const { return Eigen::Matrix3d::Identity(); } size_t opengv::relative_pose::MANoncentralRelative:: getNumberCorrespondences() const { return _numberBearingVectors2; } opengv/src/relative_pose/CentralRelativeMultiAdapter.cpp0000664016516101651610000001354413344612246022552 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::relative_pose::CentralRelativeMultiAdapter::CentralRelativeMultiAdapter( std::vector > bearingVectors1, std::vector > bearingVectors2 ) : _bearingVectors1(bearingVectors1), _bearingVectors2(bearingVectors2) { // The following variables are needed for the serialization and // de-serialization of indices size_t singleIndexOffset = 0; for( size_t pairIndex = 0; pairIndex < bearingVectors2.size(); pairIndex++ ) { singleIndexOffsets.push_back(singleIndexOffset); for( size_t correspondenceIndex = 0; correspondenceIndex < bearingVectors2[pairIndex]->size(); correspondenceIndex++ ) { multiPairIndices.push_back(pairIndex); multiKeypointIndices.push_back(correspondenceIndex); } singleIndexOffset += bearingVectors2[pairIndex]->size(); } } opengv::relative_pose::CentralRelativeMultiAdapter::~CentralRelativeMultiAdapter() {} //The multi interface!! opengv::bearingVector_t opengv::relative_pose::CentralRelativeMultiAdapter:: getBearingVector1( size_t pairIndex, size_t correspondenceIndex ) const { assert(pairIndex < _bearingVectors1.size()); assert(correspondenceIndex < _bearingVectors1[pairIndex]->size()); return (*_bearingVectors1[pairIndex])[correspondenceIndex]; } opengv::bearingVector_t opengv::relative_pose::CentralRelativeMultiAdapter:: getBearingVector2( size_t pairIndex, size_t correspondenceIndex ) const { assert(pairIndex < _bearingVectors2.size()); assert(correspondenceIndex < _bearingVectors2[pairIndex]->size()); return (*_bearingVectors2[pairIndex])[correspondenceIndex]; } double opengv::relative_pose::CentralRelativeMultiAdapter:: getWeight( size_t pairIndex, size_t correspondenceIndex ) const { return 1.0; } opengv::translation_t opengv::relative_pose::CentralRelativeMultiAdapter:: getCamOffset( size_t pairIndex ) const { return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::relative_pose::CentralRelativeMultiAdapter:: getCamRotation( size_t pairIndex ) const { return Eigen::Matrix3d::Identity(); } size_t opengv::relative_pose::CentralRelativeMultiAdapter:: getNumberCorrespondences(size_t pairIndex) const { assert(pairIndex < _bearingVectors2.size()); return _bearingVectors2[pairIndex]->size(); } size_t opengv::relative_pose::CentralRelativeMultiAdapter:: getNumberPairs() const { return _bearingVectors2.size(); } //important conversion function for the serialization of indices std::vector opengv::relative_pose::CentralRelativeMultiAdapter:: convertMultiIndices( const std::vector > & multiIndices ) const { std::vector singleIndices; for(size_t pairIndex = 0; pairIndex < multiIndices.size(); pairIndex++) { for( size_t correspondenceIndex = 0; correspondenceIndex < multiIndices[pairIndex].size(); correspondenceIndex++ ) singleIndices.push_back(convertMultiIndex( pairIndex, multiIndices[pairIndex][correspondenceIndex] )); } return singleIndices; } int opengv::relative_pose::CentralRelativeMultiAdapter:: convertMultiIndex( size_t pairIndex, size_t correspondenceIndex ) const { return singleIndexOffsets[pairIndex]+correspondenceIndex; } int opengv::relative_pose::CentralRelativeMultiAdapter:: multiPairIndex( size_t index ) const { return multiPairIndices[index]; } int opengv::relative_pose::CentralRelativeMultiAdapter:: multiCorrespondenceIndex( size_t index ) const { return multiKeypointIndices[index]; } opengv/src/math/0000775016516101651610000000000013635643413012532 5ustar dimadimaopengv/src/math/arun.cpp0000664016516101651610000000771713344612246014214 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::rotation_t opengv::math::arun( const Eigen::MatrixXd & Hcross ) { //decompose matrix H to obtain rotation Eigen::JacobiSVD< Eigen::MatrixXd > SVDcross( Hcross, Eigen::ComputeFullU | Eigen::ComputeFullV ); Eigen::Matrix3d V = SVDcross.matrixV(); Eigen::Matrix3d U = SVDcross.matrixU(); rotation_t R = V * U.transpose(); //modify the result in case the rotation has determinant=-1 if( R.determinant() < 0 ) { Eigen::Matrix3d V_prime; V_prime.col(0) = V.col(0); V_prime.col(1) = V.col(1); V_prime.col(2) = -V.col(2); R = V_prime * U.transpose(); } return R; } opengv::transformation_t opengv::math::arun_complete( const points_t & p1, const points_t & p2 ) { assert(p1.size() == p2.size()); //derive the centroid of the two point-clouds point_t pointsCenter1 = Eigen::Vector3d::Zero(); point_t pointsCenter2 = Eigen::Vector3d::Zero(); for( size_t i = 0; i < p1.size(); i++ ) { pointsCenter1 += p1[i]; pointsCenter2 += p2[i]; } pointsCenter1 = pointsCenter1 / p1.size(); pointsCenter2 = pointsCenter2 / p2.size(); //compute the matrix H = sum(f'*f^{T}) Eigen::MatrixXd Hcross(3,3); Hcross = Eigen::Matrix3d::Zero(); for( size_t i = 0; i < p1.size(); i++ ) { Eigen::Vector3d f = p1[i] - pointsCenter1; Eigen::Vector3d fprime = p2[i] - pointsCenter2; Hcross += fprime * f.transpose(); } //decompose this matrix (SVD) to obtain rotation rotation_t rotation = arun(Hcross); translation_t translation = pointsCenter1 - rotation*pointsCenter2; transformation_t solution; solution.block<3,3>(0,0) = rotation; solution.col(3) = translation; return solution; } opengv/src/math/cayley.cpp0000664016516101651610000000756013344612246014531 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::rotation_t opengv::math::cayley2rot( const cayley_t & cayley) { rotation_t R; double scale = 1+pow(cayley[0],2)+pow(cayley[1],2)+pow(cayley[2],2); R(0,0) = 1+pow(cayley[0],2)-pow(cayley[1],2)-pow(cayley[2],2); R(0,1) = 2*(cayley[0]*cayley[1]-cayley[2]); R(0,2) = 2*(cayley[0]*cayley[2]+cayley[1]); R(1,0) = 2*(cayley[0]*cayley[1]+cayley[2]); R(1,1) = 1-pow(cayley[0],2)+pow(cayley[1],2)-pow(cayley[2],2); R(1,2) = 2*(cayley[1]*cayley[2]-cayley[0]); R(2,0) = 2*(cayley[0]*cayley[2]-cayley[1]); R(2,1) = 2*(cayley[1]*cayley[2]+cayley[0]); R(2,2) = 1-pow(cayley[0],2)-pow(cayley[1],2)+pow(cayley[2],2); R = (1/scale) * R; return R; } opengv::rotation_t opengv::math::cayley2rot_reduced( const cayley_t & cayley) { rotation_t R; R(0,0) = 1+pow(cayley[0],2)-pow(cayley[1],2)-pow(cayley[2],2); R(0,1) = 2*(cayley[0]*cayley[1]-cayley[2]); R(0,2) = 2*(cayley[0]*cayley[2]+cayley[1]); R(1,0) = 2*(cayley[0]*cayley[1]+cayley[2]); R(1,1) = 1-pow(cayley[0],2)+pow(cayley[1],2)-pow(cayley[2],2); R(1,2) = 2*(cayley[1]*cayley[2]-cayley[0]); R(2,0) = 2*(cayley[0]*cayley[2]-cayley[1]); R(2,1) = 2*(cayley[1]*cayley[2]+cayley[0]); R(2,2) = 1-pow(cayley[0],2)-pow(cayley[1],2)+pow(cayley[2],2); return R; } opengv::cayley_t opengv::math::rot2cayley( const rotation_t & R ) { Eigen::Matrix3d C1; Eigen::Matrix3d C2; Eigen::Matrix3d C; C1 = R-Eigen::Matrix3d::Identity(); C2 = R+Eigen::Matrix3d::Identity(); C = C1 * C2.inverse(); cayley_t cayley; cayley[0] = -C(1,2); cayley[1] = C(0,2); cayley[2] = -C(0,1); return cayley; } opengv/src/math/roots.cpp0000664016516101651610000001531213635643413014406 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include std::vector opengv::math::o3_roots( const std::vector & p ) { const double & a = p[0]; const double & b = p[1]; const double & c = p[2]; const double & d = p[3]; double theta_0 = b*b - 3.0*a*c; double theta_1 = 2.0*b*b*b - 9.0*a*b*c + 27.0*a*a*d; double term = theta_1 * theta_1 - 4.0 * theta_0 * theta_0 * theta_0; std::complex u1( 1.0, 0.0); std::complex u2(-0.5, 0.5*sqrt(3.0)); std::complex u3(-0.5,-0.5*sqrt(3.0)); std::complex C; if( term >= 0.0 ) { double C3 = 0.5 * (theta_1 + sqrt(term)); if( C3 < 0.0 ) C = std::complex(-pow(-C3,(1.0/3.0)),0.0); else C = std::complex( pow( C3,(1.0/3.0)),0.0); } else { std::complex C3( 0.5*theta_1, 0.5*sqrt(-term) ); //take the third root of this complex number double r3 = sqrt(pow(C3.real(),2.0)+pow(C3.imag(),2.0)); double a3 = atan(C3.imag() / C3.real()); if( C3.real() < 0 ) a3 += M_PI; double r = pow(r3,(1.0/3.0)); C = std::complex(r*cos(a3/3.0),r*sin(a3/3.0)); } std::complex r1 = -(1.0/(3.0*a)) * (b + u1*C + theta_0 / (u1*C) ); std::complex r2 = -(1.0/(3.0*a)) * (b + u2*C + theta_0 / (u2*C) ); std::complex r3 = -(1.0/(3.0*a)) * (b + u3*C + theta_0 / (u3*C) ); std::vector roots; roots.push_back(r1.real()); roots.push_back(r2.real()); roots.push_back(r3.real()); return roots; } std::vector opengv::math::o4_roots( const Eigen::MatrixXd & p ) { double A = p(0,0); double B = p(1,0); double C = p(2,0); double D = p(3,0); double E = p(4,0); double A_pw2 = A*A; double B_pw2 = B*B; double A_pw3 = A_pw2*A; double B_pw3 = B_pw2*B; double A_pw4 = A_pw3*A; double B_pw4 = B_pw3*B; double alpha = -3*B_pw2/(8*A_pw2)+C/A; double beta = B_pw3/(8*A_pw3)-B*C/(2*A_pw2)+D/A; double gamma = -3*B_pw4/(256*A_pw4)+B_pw2*C/(16*A_pw3)-B*D/(4*A_pw2)+E/A; double alpha_pw2 = alpha*alpha; double alpha_pw3 = alpha_pw2*alpha; std::complex P (-alpha_pw2/12-gamma,0); std::complex Q (-alpha_pw3/108+alpha*gamma/3-pow(beta,2)/8,0); std::complex R = -Q/2.0+sqrt(pow(Q,2.0)/4.0+pow(P,3.0)/27.0); std::complex U = pow(R,(1.0/3.0)); std::complex y; if (U.real() == 0) y = -5.0*alpha/6.0-pow(Q,(1.0/3.0)); else y = -5.0*alpha/6.0-P/(3.0*U)+U; std::complex w = sqrt(alpha+2.0*y); std::vector realRoots; std::complex temp; temp = -B/(4.0*A) + 0.5*(w+sqrt(-(3.0*alpha+2.0*y+2.0*beta/w))); realRoots.push_back(temp.real()); temp = -B/(4.0*A) + 0.5*(w-sqrt(-(3.0*alpha+2.0*y+2.0*beta/w))); realRoots.push_back(temp.real()); temp = -B/(4.0*A) + 0.5*(-w+sqrt(-(3.0*alpha+2.0*y-2.0*beta/w))); realRoots.push_back(temp.real()); temp = -B/(4.0*A) + 0.5*(-w-sqrt(-(3.0*alpha+2.0*y-2.0*beta/w))); realRoots.push_back(temp.real()); return realRoots; } std::vector opengv::math::o4_roots( const std::vector & p ) { double A = p[0]; double B = p[1]; double C = p[2]; double D = p[3]; double E = p[4]; double A_pw2 = A*A; double B_pw2 = B*B; double A_pw3 = A_pw2*A; double B_pw3 = B_pw2*B; double A_pw4 = A_pw3*A; double B_pw4 = B_pw3*B; double alpha = -3*B_pw2/(8*A_pw2)+C/A; double beta = B_pw3/(8*A_pw3)-B*C/(2*A_pw2)+D/A; double gamma = -3*B_pw4/(256*A_pw4)+B_pw2*C/(16*A_pw3)-B*D/(4*A_pw2)+E/A; double alpha_pw2 = alpha*alpha; double alpha_pw3 = alpha_pw2*alpha; std::complex P (-alpha_pw2/12-gamma,0); std::complex Q (-alpha_pw3/108+alpha*gamma/3-pow(beta,2)/8,0); std::complex R = -Q/2.0+sqrt(pow(Q,2.0)/4.0+pow(P,3.0)/27.0); std::complex U = pow(R,(1.0/3.0)); std::complex y; if (U.real() == 0) y = -5.0*alpha/6.0-pow(Q,(1.0/3.0)); else y = -5.0*alpha/6.0-P/(3.0*U)+U; std::complex w = sqrt(alpha+2.0*y); std::vector realRoots; std::complex temp; temp = -B/(4.0*A) + 0.5*(w+sqrt(-(3.0*alpha+2.0*y+2.0*beta/w))); realRoots.push_back(temp.real()); temp = -B/(4.0*A) + 0.5*(w-sqrt(-(3.0*alpha+2.0*y+2.0*beta/w))); realRoots.push_back(temp.real()); temp = -B/(4.0*A) + 0.5*(-w+sqrt(-(3.0*alpha+2.0*y-2.0*beta/w))); realRoots.push_back(temp.real()); temp = -B/(4.0*A) + 0.5*(-w-sqrt(-(3.0*alpha+2.0*y-2.0*beta/w))); realRoots.push_back(temp.real()); return realRoots; } opengv/src/math/Sturm.cpp0000664016516101651610000003270513635643413014357 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include opengv::math::Bracket::Bracket( double lowerBound, double upperBound ) : _lowerBound(lowerBound), _upperBound(upperBound), _lowerBoundChangesComputed(false), _upperBoundChangesComputed(false), _lowerBoundChanges(0), _upperBoundChanges(0) {} opengv::math::Bracket::Bracket( double lowerBound, double upperBound, size_t changes, bool setUpperBoundChanges ) : _lowerBound(lowerBound), _upperBound(upperBound), _lowerBoundChangesComputed(false), _upperBoundChangesComputed(false), _lowerBoundChanges(0), _upperBoundChanges(0) { if( setUpperBoundChanges ) { _upperBoundChanges = changes; _upperBoundChangesComputed = true; } else { _lowerBoundChanges = changes; _lowerBoundChangesComputed = true; } } opengv::math::Bracket::~Bracket() {} bool opengv::math::Bracket::dividable( double eps ) const { if( numberRoots() == 1 && (_upperBound - _lowerBound ) < eps ) return false; if( numberRoots() == 0 ) return false; double center = (_upperBound + _lowerBound) / 2.0; if( center == _upperBound || center == _lowerBound) return false; return true; } void opengv::math::Bracket::divide( std::list & brackets ) const { double center = (_upperBound + _lowerBound) / 2.0; Ptr lowerBracket(new Bracket(_lowerBound,center,_lowerBoundChanges,false)); Ptr upperBracket(new Bracket(center,_upperBound,_upperBoundChanges,true)); brackets.push_back(lowerBracket); brackets.push_back(upperBracket); } double opengv::math::Bracket::lowerBound() const { return _lowerBound; } double opengv::math::Bracket::upperBound() const { return _upperBound; } bool opengv::math::Bracket::lowerBoundChangesComputed() const { return _lowerBoundChangesComputed; } bool opengv::math::Bracket::upperBoundChangesComputed() const { return _upperBoundChangesComputed; } void opengv::math::Bracket::setLowerBoundChanges( size_t changes ) { _lowerBoundChanges = changes; _lowerBoundChangesComputed = true; } void opengv::math::Bracket::setUpperBoundChanges( size_t changes ) { _upperBoundChanges = changes; _upperBoundChangesComputed = true; } size_t opengv::math::Bracket::numberRoots() const { if( !_lowerBoundChangesComputed || !_upperBoundChangesComputed ) { std::cout << "Error: cannot evaluate number of roots" < & p ) : _C(Eigen::MatrixXd(p.size(),p.size())) { _dimension = (size_t) _C.cols(); _C = Eigen::MatrixXd(_dimension,_dimension); _C.setZero(); for( size_t i = 0; i < _dimension; i++ ) _C(0,i) = p[i]; for( size_t i = 1; i < _dimension; i++ ) _C(1,i) = _C(0,i-1) * (_dimension-i); for( size_t i = 2; i < _dimension; i++ ) { Eigen::MatrixXd p1 = _C.block(i-2,i-2,1,_dimension-(i-2)); Eigen::MatrixXd p2 = _C.block(i-1,i-1,1,_dimension-(i-1)); Eigen::MatrixXd r; computeNegatedRemainder(p1,p2,r); _C.block(i,i,1,_dimension-i) = r.block(0,2,1,_dimension-i); } } opengv::math::Sturm::~Sturm() {}; void opengv::math::Sturm::findRoots2( std::vector & roots, double eps_x, double eps_val ) { double absoluteBound = computeLagrangianBound(); std::list stack; stack.push_back(Bracket::Ptr(new Bracket(-absoluteBound,absoluteBound))); stack.back()->setLowerBoundChanges( evaluateChain2(stack.back()->lowerBound()) ); stack.back()->setUpperBoundChanges( evaluateChain2(stack.back()->upperBound()) ); roots.reserve(stack.back()->numberRoots()); //some variables for pollishing Eigen::MatrixXd monomials(_dimension,1); monomials(_dimension-1,0) = 1.0; while( !stack.empty() ) { Bracket::Ptr bracket = stack.front(); stack.pop_front(); if( bracket->dividable(eps_x) ) { bool divide = true; if( bracket->numberRoots() == 1 ) { //new part, we try immediately to do the pollishing here bool converged = false; double root = 0.5 * (bracket->lowerBound() + bracket->upperBound()); for(size_t i = 2; i <= _dimension; i++) monomials(_dimension-i,0) = monomials(_dimension-i+1,0)*root; Eigen::MatrixXd matValue = _C.row(0) * monomials; double value = matValue(0,0); while( !converged ) { Eigen::MatrixXd matDerivative = _C.row(1) * monomials; double derivative = matDerivative(0,0); double newRoot = root - (value/derivative); if( newRoot < bracket->lowerBound() || newRoot > bracket->upperBound() ) break; for(size_t i = 2; i <= _dimension; i++) monomials(_dimension-i,0) = monomials(_dimension-i+1,0)*newRoot; matValue = _C.row(0) * monomials; double newValue = matValue(0,0); if( fabs(newValue) > fabs(value) ) break; //do update value = newValue; root = newRoot; //check if converged if( fabs(value) < eps_val ) converged = true; } if( converged ) { divide = false; roots.push_back(root); } } if(divide) { bracket->divide(stack); std::list::iterator it = stack.end(); it--; size_t changes = evaluateChain2((*it)->lowerBound()); (*it)->setLowerBoundChanges(changes); it--; (*it)->setUpperBoundChanges(changes); } } else { if( bracket->numberRoots() > 0 ) roots.push_back(0.5 * (bracket->lowerBound() + bracket->upperBound())); } } } std::vector opengv::math::Sturm::findRoots() { //bracket the roots std::vector roots; bracketRoots(roots); //pollish Eigen::MatrixXd monomials(_dimension,1); monomials(_dimension-1,0) = 1.0; for(size_t r = 0; r < roots.size(); r++ ) { //Now do Gauss iterations here //evaluate all monomials at the left bound for(size_t k = 0; k < 5; k++ ) { for(size_t i = 2; i <= _dimension; i++) monomials(_dimension-i,0) = monomials(_dimension-i+1,0)*roots[r]; Eigen::MatrixXd value = _C.row(0) * monomials; Eigen::MatrixXd derivative = _C.row(1) * monomials; //correction roots[r] = roots[r] - (value(0,0)/derivative(0,0)); } } return roots; } void opengv::math::Sturm::bracketRoots( std::vector & roots, double eps ) { double absoluteBound = computeLagrangianBound(); std::list stack; stack.push_back(Bracket::Ptr(new Bracket(-absoluteBound,absoluteBound))); stack.back()->setLowerBoundChanges( evaluateChain2(stack.back()->lowerBound()) ); stack.back()->setUpperBoundChanges( evaluateChain2(stack.back()->upperBound()) ); double localEps = eps; if( eps < 0.0 ) localEps = absoluteBound / (10.0 * stack.back()->numberRoots()); roots.reserve(stack.back()->numberRoots()); while( !stack.empty() ) { Bracket::Ptr bracket = stack.front(); stack.pop_front(); if( bracket->dividable( localEps) ) { bracket->divide(stack); std::list::iterator it = stack.end(); it--; size_t changes = evaluateChain2((*it)->lowerBound()); (*it)->setLowerBoundChanges(changes); it--; (*it)->setUpperBoundChanges(changes); } else { if( bracket->numberRoots() > 0 ) roots.push_back(0.5 * (bracket->lowerBound() + bracket->upperBound())); } } } size_t opengv::math::Sturm::evaluateChain( double bound ) { Eigen::MatrixXd monomials(_dimension,1); monomials(_dimension-1,0) = 1.0; //evaluate all monomials at the bound for(size_t i = 2; i <= _dimension; i++) monomials(_dimension-i,0) = monomials(_dimension-i+1,0)*bound; Eigen::MatrixXd signs(_dimension,1); for( size_t i = 0; i < _dimension; i++ ) signs.block(i,0,1,1) = _C.block(i,i,1,_dimension-i) * monomials.block(i,0,_dimension-i,1); bool positive = false; if( signs(0,0) > 0.0 ) positive = true; int signChanges = 0; for( size_t i = 1; i < _dimension; i++ ) { if( positive ) { if( signs(i,0) < 0.0 ) { signChanges++; positive = false; } } else { if( signs(i,0) > 0.0 ) { signChanges++; positive = true; } } } return signChanges; } size_t opengv::math::Sturm::evaluateChain2( double bound ) { std::vector monomials; monomials.resize(_dimension); monomials[_dimension-1] = 1.0; //evaluate all monomials at the bound for(size_t i = 2; i <= _dimension; i++) monomials[_dimension-i] = monomials[_dimension-i+1]*bound; std::vector signs; signs.reserve(_dimension); for( size_t i = 0; i < _dimension; i++ ) { signs.push_back(0.0); for( size_t j = i; j < _dimension; j++ ) signs.back() += _C(i,j) * monomials[j]; } bool positive = false; if( signs[0] > 0.0 ) positive = true; int signChanges = 0; for( size_t i = 1; i < _dimension; i++ ) { if( positive ) { if( signs[i] < 0.0 ) { signChanges++; positive = false; } } else { if( signs[i] > 0.0 ) { signChanges++; positive = true; } } } return signChanges; } void opengv::math::Sturm::computeNegatedRemainder( const Eigen::MatrixXd & p1, const Eigen::MatrixXd & p2, Eigen::MatrixXd & r ) { //we have to create 3 subtraction polynomials Eigen::MatrixXd poly_1(1,p1.cols()); poly_1.block(0,0,1,p2.cols()) = (p1(0,0)/p2(0,0)) * p2; poly_1(0,p1.cols()-1) = 0.0; Eigen::MatrixXd poly_2(1,p1.cols()); poly_2.block(0,1,1,p2.cols()) = (p1(0,1)/p2(0,0)) * p2; poly_2(0,0) = 0.0; Eigen::MatrixXd poly_3(1,p1.cols()); poly_3.block(0,1,1,p2.cols()) = (-p2(0,1)*p1(0,0)/pow(p2(0,0),2)) * p2; poly_3(0,0) = 0.0; //compute remainder r = -p1 + poly_1 + poly_2 + poly_3; } double opengv::math::Sturm::computeLagrangianBound() { std::vector coefficients; coefficients.reserve(_dimension-1); for(size_t i=0; i < _dimension-1; i++) coefficients.push_back(pow(fabs(_C(0,i+1)/_C(0,0)),(1.0/(i+1)))); size_t j = 0; double max1 = -1.0; for( size_t i = 0; i < coefficients.size(); i++ ) { if( coefficients[i] > max1 ) { j = i; max1 = coefficients[i]; } } coefficients[j] = -1.0; double max2 = -1.0; for( size_t i=0; i < coefficients.size(); i++ ) { if( coefficients[i] > max2 ) max2 = coefficients[i]; } double bound = max1 + max2; return bound; } opengv/src/math/quaternion.cpp0000664016516101651610000001066213344612246015425 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::rotation_t opengv::math::quaternion2rot( const quaternion_t & q) { rotation_t R; R(0,0) = pow(q[0],2)+pow(q[1],2)-pow(q[2],2)-pow(q[3],2); R(0,1) = 2.0*(q[1]*q[2]-q[0]*q[3]); R(0,2) = 2.0*(q[1]*q[3]+q[0]*q[2]); R(1,0) = 2.0*(q[1]*q[2]+q[0]*q[3]); R(1,1) = pow(q[0],2)-pow(q[1],2)+pow(q[2],2)-pow(q[3],2); R(1,2) = 2.0*(q[2]*q[3]-q[0]*q[1]); R(2,0) = 2.0*(q[1]*q[3]-q[0]*q[2]); R(2,1) = 2.0*(q[2]*q[3]+q[0]*q[1]); R(2,2) = pow(q[0],2)-pow(q[1],2)-pow(q[2],2)+pow(q[3],2); return R; } opengv::quaternion_t opengv::math::rot2quaternion( const rotation_t & R ) { quaternion_t q; q[0] = ( R(0,0) + R(1,1) + R(2,2) + 1.0) / 4.0; q[1] = ( R(0,0) - R(1,1) - R(2,2) + 1.0) / 4.0; q[2] = (-R(0,0) + R(1,1) - R(2,2) + 1.0) / 4.0; q[3] = (-R(0,0) - R(1,1) + R(2,2) + 1.0) / 4.0; if(q[0] < 0.0) q[0] = 0.0; if(q[1] < 0.0) q[1] = 0.0; if(q[2] < 0.0) q[2] = 0.0; if(q[3] < 0.0) q[3] = 0.0; q[0] = sqrt(q[0]); q[1] = sqrt(q[1]); q[2] = sqrt(q[2]); q[3] = sqrt(q[3]); if(q[0] >= q[1] && q[0] >= q[2] && q[0] >= q[3]) { q[0] *= +1.0; q[1] *= ((R(2,1)-R(1,2))/fabs(R(2,1)-R(1,2))); q[2] *= ((R(0,2)-R(2,0))/fabs(R(0,2)-R(2,0))); q[3] *= ((R(1,0)-R(0,1))/fabs(R(1,0)-R(0,1))); } else if(q[1] >= q[0] && q[1] >= q[2] && q[1] >= q[3]) { q[0] *= ((R(2,1)-R(1,2))/fabs(R(2,1)-R(1,2))); q[1] *= +1.0; q[2] *= ((R(1,0)+R(0,1))/fabs(R(1,0)+R(0,1))); q[3] *= ((R(0,2)+R(2,0))/fabs(R(0,2)+R(2,0))); } else if(q[2] >= q[0] && q[2] >= q[1] && q[2] >= q[3]) { q[0] *= ((R(0,2)-R(2,0))/fabs(R(0,2)-R(2,0))); q[1] *= ((R(1,0)+R(0,1))/fabs(R(1,0)+R(0,1))); q[2] *= +1.0; q[3] *= ((R(2,1)+R(1,2))/fabs(R(2,1)+R(1,2))); } else if(q[3] >= q[0] && q[3] >= q[1] && q[3] >= q[2]) { q[0] *= ((R(1,0)-R(0,1))/fabs(R(1,0)-R(0,1))); q[1] *= ((R(2,0)+R(0,2))/fabs(R(2,0)+R(0,2))); q[2] *= ((R(2,1)+R(1,2))/fabs(R(2,1)+R(1,2))); q[3] *= +1.0; } else {};/*std::cout << "quaternion error" << std::endl;*/ double scale = sqrt(q[0]*q[0]+q[1]*q[1]+q[2]*q[2]+q[3]*q[3]); q[0] /= scale; q[1] /= scale; q[2] /= scale; q[3] /= scale; return q; } opengv/src/math/gauss_jordan.cpp0000664016516101651610000001276413344612246015724 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include void opengv::math::gauss_jordan( std::vector*> & matrix, int exitCondition ) { //create some constants for zero-checking etc. double precision = 1.0e-10; int rows = matrix.size(); int cols = matrix[0]->size(); //the working row int frontRow; //first step down for( frontRow = 0; frontRow < rows; frontRow++ ) { // first iterate through the rows and find the row that has the biggest // leading coefficient double maxValue = -1.0; int row = -1; for( int tempRow = frontRow; tempRow < rows; tempRow++ ) { double value = fabs((*(matrix[tempRow]))[frontRow]); if( value > maxValue ) { row = tempRow; maxValue = value; } } //rowIter is now the row that should go in the place of frontRow->swap std::swap( matrix[row], matrix[frontRow] ); //ok, now use frontRow! //first divide all coefficients by the leading coefficient int col = frontRow; double leadingCoefficient_inv = 1.0 / (*(matrix[frontRow]))[col]; (*(matrix[frontRow]))[col] = 1.0; ++col; while( col < cols ) { (*(matrix[frontRow]))[col] *= leadingCoefficient_inv; ++col; } //create a vector of bools indicating the cols that need to be manipulated col = frontRow; std::vector nonzeroIdx; nonzeroIdx.reserve( cols - frontRow ); while( col < cols ) { if( fabs(((*(matrix[frontRow]))[col])) > precision ) nonzeroIdx.push_back(col); col++; } //iterate through all remaining rows, and subtract correct multiple of //first row (if leading coefficient is non-zero!) row = frontRow; ++row; while( row < rows ) { col = frontRow; double leadingCoefficient = (*(matrix[row]))[col]; if( fabs(leadingCoefficient) > precision ) { for( int col = 0; col < (int) nonzeroIdx.size(); col++ ) (*(matrix[row]))[nonzeroIdx[col]] -= leadingCoefficient * ((*(matrix[frontRow]))[nonzeroIdx[col]]); } ++row; } } //set index to the last non-zero row --frontRow; //Now step up while( frontRow > exitCondition ) { //create a vector of bools indicating the cols that need to be manipulated int col = frontRow; std::vector nonzeroIdx; nonzeroIdx.reserve( cols - frontRow ); while( col < cols ) { if( fabs(((*(matrix[frontRow]))[col])) > precision ) nonzeroIdx.push_back(col); col++; } //get the working row int row = frontRow; do { //decrement working row --row; //working column //now get the leading coefficient double leadingCoefficient = (*(matrix[row]))[frontRow]; //Now iterator until the end, and subtract each time the multiplied //front-row if( fabs(leadingCoefficient) > precision ) { for( int col = 0; col < (int) nonzeroIdx.size(); col++ ) (*(matrix[row]))[nonzeroIdx[col]] -= leadingCoefficient * (*(matrix[frontRow]))[nonzeroIdx[col]]; } } while( row > exitCondition ); --frontRow; } } opengv/src/absolute_pose/0000775016516101651610000000000013344612246014442 5ustar dimadimaopengv/src/absolute_pose/modules/0000775016516101651610000000000013635643413016115 5ustar dimadimaopengv/src/absolute_pose/modules/gpnp2/0000775016516101651610000000000013344612246017140 5ustar dimadimaopengv/src/absolute_pose/modules/gpnp2/reductors.cpp0000664016516101651610000001033213344612246021655 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp2::groebnerRow5_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(5,1); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,2) -= factor * groebnerMatrix(5,2); groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(5,3); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(5,4); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(5,5); } void opengv::absolute_pose::modules::gpnp2::groebnerRow6_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,2) / groebnerMatrix(6,2); groebnerMatrix(targetRow,2) = 0.0; groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(6,3); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(6,4); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(6,5); } void opengv::absolute_pose::modules::gpnp2::groebnerRow7_10_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(7,3); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,2) -= factor * groebnerMatrix(7,4); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(7,5); } void opengv::absolute_pose::modules::gpnp2::groebnerRow7_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,3) / groebnerMatrix(7,3); groebnerMatrix(targetRow,3) = 0.0; groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(7,4); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(7,5); } void opengv::absolute_pose::modules::gpnp2::groebnerRow8_00_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,4) / groebnerMatrix(8,4); groebnerMatrix(targetRow,4) = 0.0; groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(8,5); } opengv/src/absolute_pose/modules/gpnp2/spolynomials.cpp0000664016516101651610000001242113344612246022375 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp2::sPolynomial5( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(5,1) = (groebnerMatrix(0,1)/(groebnerMatrix(0,0))-groebnerMatrix(1,1)/(groebnerMatrix(1,0))); groebnerMatrix(5,2) = (groebnerMatrix(0,2)/(groebnerMatrix(0,0))-groebnerMatrix(1,2)/(groebnerMatrix(1,0))); groebnerMatrix(5,3) = (groebnerMatrix(0,3)/(groebnerMatrix(0,0))-groebnerMatrix(1,3)/(groebnerMatrix(1,0))); groebnerMatrix(5,4) = (groebnerMatrix(0,4)/(groebnerMatrix(0,0))-groebnerMatrix(1,4)/(groebnerMatrix(1,0))); groebnerMatrix(5,5) = (groebnerMatrix(0,5)/(groebnerMatrix(0,0))-groebnerMatrix(1,5)/(groebnerMatrix(1,0))); } void opengv::absolute_pose::modules::gpnp2::sPolynomial6( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(6,1) = (groebnerMatrix(1,1)/(groebnerMatrix(1,0))-groebnerMatrix(2,1)/(groebnerMatrix(2,0))); groebnerMatrix(6,2) = (groebnerMatrix(1,2)/(groebnerMatrix(1,0))-groebnerMatrix(2,2)/(groebnerMatrix(2,0))); groebnerMatrix(6,3) = (groebnerMatrix(1,3)/(groebnerMatrix(1,0))-groebnerMatrix(2,3)/(groebnerMatrix(2,0))); groebnerMatrix(6,4) = (groebnerMatrix(1,4)/(groebnerMatrix(1,0))-groebnerMatrix(2,4)/(groebnerMatrix(2,0))); groebnerMatrix(6,5) = (groebnerMatrix(1,5)/(groebnerMatrix(1,0))-groebnerMatrix(2,5)/(groebnerMatrix(2,0))); } void opengv::absolute_pose::modules::gpnp2::sPolynomial7( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(7,1) = (groebnerMatrix(2,1)/(groebnerMatrix(2,0))-groebnerMatrix(3,1)/(groebnerMatrix(3,0))); groebnerMatrix(7,2) = (groebnerMatrix(2,2)/(groebnerMatrix(2,0))-groebnerMatrix(3,2)/(groebnerMatrix(3,0))); groebnerMatrix(7,3) = (groebnerMatrix(2,3)/(groebnerMatrix(2,0))-groebnerMatrix(3,3)/(groebnerMatrix(3,0))); groebnerMatrix(7,4) = (groebnerMatrix(2,4)/(groebnerMatrix(2,0))-groebnerMatrix(3,4)/(groebnerMatrix(3,0))); groebnerMatrix(7,5) = (groebnerMatrix(2,5)/(groebnerMatrix(2,0))-groebnerMatrix(3,5)/(groebnerMatrix(3,0))); } void opengv::absolute_pose::modules::gpnp2::sPolynomial8( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(8,1) = (groebnerMatrix(3,1)/(groebnerMatrix(3,0))-groebnerMatrix(4,1)/(groebnerMatrix(4,0))); groebnerMatrix(8,2) = (groebnerMatrix(3,2)/(groebnerMatrix(3,0))-groebnerMatrix(4,2)/(groebnerMatrix(4,0))); groebnerMatrix(8,3) = (groebnerMatrix(3,3)/(groebnerMatrix(3,0))-groebnerMatrix(4,3)/(groebnerMatrix(4,0))); groebnerMatrix(8,4) = (groebnerMatrix(3,4)/(groebnerMatrix(3,0))-groebnerMatrix(4,4)/(groebnerMatrix(4,0))); groebnerMatrix(8,5) = (groebnerMatrix(3,5)/(groebnerMatrix(3,0))-groebnerMatrix(4,5)/(groebnerMatrix(4,0))); } void opengv::absolute_pose::modules::gpnp2::sPolynomial9( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(9,3) = groebnerMatrix(6,3)/(groebnerMatrix(6,2)); groebnerMatrix(9,4) = (groebnerMatrix(6,4)/(groebnerMatrix(6,2))-groebnerMatrix(8,5)/(groebnerMatrix(8,4))); groebnerMatrix(9,5) = groebnerMatrix(6,5)/(groebnerMatrix(6,2)); } opengv/src/absolute_pose/modules/gpnp2/init.cpp0000664016516101651610000002213513344612246020612 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp2::init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ) { Eigen::Vector3d temp = c0-c1; double c01w = temp.norm()*temp.norm(); temp = c0-c2; double c02w = temp.norm()*temp.norm(); temp = c0-c3; double c03w = temp.norm()*temp.norm(); temp = c1-c2; double c12w = temp.norm()*temp.norm(); temp = c1-c3; double c13w = temp.norm()*temp.norm(); groebnerMatrix(0,0) = ((((((((-2*m(0,0)*m(3,0)-2*m(1,0)*m(4,0))-2*m(2,0)*m(5,0))+pow(m(0,0),2))+pow(m(3,0),2))+pow(m(1,0),2))+pow(m(4,0),2))+pow(m(2,0),2))+pow(m(5,0),2)); groebnerMatrix(0,1) = (((((((((((2*n(0,0)*m(0,0)-2*n(0,0)*m(3,0))-2*m(0,0)*n(3,0))+2*n(3,0)*m(3,0))+2*n(1,0)*m(1,0))-2*n(1,0)*m(4,0))-2*m(1,0)*n(4,0))+2*n(4,0)*m(4,0))+2*n(2,0)*m(2,0))-2*n(2,0)*m(5,0))-2*m(2,0)*n(5,0))+2*n(5,0)*m(5,0)); groebnerMatrix(0,2) = ((((((((-2*n(0,0)*n(3,0)-2*n(1,0)*n(4,0))-2*n(2,0)*n(5,0))+pow(n(0,0),2))+pow(n(3,0),2))+pow(n(1,0),2))+pow(n(4,0),2))+pow(n(2,0),2))+pow(n(5,0),2)); groebnerMatrix(0,3) = (((((((((((2*a(0,0)*m(0,0)-2*a(0,0)*m(3,0))-2*m(0,0)*a(3,0))+2*a(3,0)*m(3,0))+2*a(1,0)*m(1,0))-2*a(1,0)*m(4,0))-2*m(1,0)*a(4,0))+2*a(4,0)*m(4,0))+2*a(2,0)*m(2,0))-2*a(2,0)*m(5,0))-2*m(2,0)*a(5,0))+2*a(5,0)*m(5,0)); groebnerMatrix(0,4) = (((((((((((2*a(0,0)*n(0,0)-2*a(0,0)*n(3,0))-2*n(0,0)*a(3,0))+2*a(3,0)*n(3,0))+2*a(1,0)*n(1,0))-2*a(1,0)*n(4,0))-2*n(1,0)*a(4,0))+2*a(4,0)*n(4,0))+2*a(2,0)*n(2,0))-2*a(2,0)*n(5,0))-2*n(2,0)*a(5,0))+2*a(5,0)*n(5,0)); groebnerMatrix(0,5) = (((((((((-c01w+pow(a(0,0),2))-2*a(0,0)*a(3,0))+pow(a(3,0),2))+pow(a(1,0),2))-2*a(1,0)*a(4,0))+pow(a(4,0),2))+pow(a(2,0),2))-2*a(2,0)*a(5,0))+pow(a(5,0),2)); groebnerMatrix(1,0) = ((((((((-2*m(0,0)*m(6,0)-2*m(1,0)*m(7,0))-2*m(2,0)*m(8,0))+pow(m(0,0),2))+pow(m(1,0),2))+pow(m(2,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2)); groebnerMatrix(1,1) = (((((((((((2*n(0,0)*m(0,0)+2*n(1,0)*m(1,0))+2*n(2,0)*m(2,0))-2*n(0,0)*m(6,0))-2*m(0,0)*n(6,0))+2*n(6,0)*m(6,0))-2*n(1,0)*m(7,0))-2*m(1,0)*n(7,0))+2*n(7,0)*m(7,0))-2*n(2,0)*m(8,0))-2*m(2,0)*n(8,0))+2*n(8,0)*m(8,0)); groebnerMatrix(1,2) = ((((((((-2*n(0,0)*n(6,0)-2*n(1,0)*n(7,0))-2*n(2,0)*n(8,0))+pow(n(0,0),2))+pow(n(1,0),2))+pow(n(2,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2)); groebnerMatrix(1,3) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))-2*a(0,0)*m(6,0))-2*m(0,0)*a(6,0))+2*a(6,0)*m(6,0))-2*a(1,0)*m(7,0))-2*m(1,0)*a(7,0))+2*a(7,0)*m(7,0))-2*a(2,0)*m(8,0))-2*m(2,0)*a(8,0))+2*a(8,0)*m(8,0)); groebnerMatrix(1,4) = (((((((((((2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))-2*a(0,0)*n(6,0))-2*n(0,0)*a(6,0))+2*a(6,0)*n(6,0))-2*a(1,0)*n(7,0))-2*n(1,0)*a(7,0))+2*a(7,0)*n(7,0))-2*a(2,0)*n(8,0))-2*n(2,0)*a(8,0))+2*a(8,0)*n(8,0)); groebnerMatrix(1,5) = (((((((((-c02w+pow(a(0,0),2))+pow(a(1,0),2))+pow(a(2,0),2))-2*a(0,0)*a(6,0))+pow(a(6,0),2))-2*a(1,0)*a(7,0))+pow(a(7,0),2))-2*a(2,0)*a(8,0))+pow(a(8,0),2)); groebnerMatrix(2,0) = ((((((((-2*m(0,0)*m(9,0)-2*m(1,0)*m(10,0))-2*m(2,0)*m(11,0))+pow(m(0,0),2))+pow(m(1,0),2))+pow(m(2,0),2))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2)); groebnerMatrix(2,1) = (((((((((((2*n(0,0)*m(0,0)+2*n(1,0)*m(1,0))+2*n(2,0)*m(2,0))-2*n(0,0)*m(9,0))-2*m(0,0)*n(9,0))+2*n(9,0)*m(9,0))-2*n(1,0)*m(10,0))-2*m(1,0)*n(10,0))+2*n(10,0)*m(10,0))-2*n(2,0)*m(11,0))-2*m(2,0)*n(11,0))+2*n(11,0)*m(11,0)); groebnerMatrix(2,2) = ((((((((-2*n(0,0)*n(9,0)-2*n(1,0)*n(10,0))-2*n(2,0)*n(11,0))+pow(n(0,0),2))+pow(n(1,0),2))+pow(n(2,0),2))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2)); groebnerMatrix(2,3) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))-2*a(0,0)*m(9,0))-2*m(0,0)*a(9,0))+2*a(9,0)*m(9,0))-2*a(1,0)*m(10,0))-2*m(1,0)*a(10,0))+2*a(10,0)*m(10,0))-2*a(2,0)*m(11,0))-2*m(2,0)*a(11,0))+2*a(11,0)*m(11,0)); groebnerMatrix(2,4) = (((((((((((2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))-2*a(0,0)*n(9,0))-2*n(0,0)*a(9,0))+2*a(9,0)*n(9,0))-2*a(1,0)*n(10,0))-2*n(1,0)*a(10,0))+2*a(10,0)*n(10,0))-2*a(2,0)*n(11,0))-2*n(2,0)*a(11,0))+2*a(11,0)*n(11,0)); groebnerMatrix(2,5) = (((((((((-c03w+pow(a(0,0),2))+pow(a(1,0),2))+pow(a(2,0),2))-2*a(0,0)*a(9,0))+pow(a(9,0),2))-2*a(1,0)*a(10,0))+pow(a(10,0),2))-2*a(2,0)*a(11,0))+pow(a(11,0),2)); groebnerMatrix(3,0) = ((((((((-2*m(3,0)*m(6,0)-2*m(4,0)*m(7,0))-2*m(5,0)*m(8,0))+pow(m(3,0),2))+pow(m(4,0),2))+pow(m(5,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2)); groebnerMatrix(3,1) = (((((((((((2*n(3,0)*m(3,0)+2*n(4,0)*m(4,0))+2*n(5,0)*m(5,0))+2*n(6,0)*m(6,0))+2*n(7,0)*m(7,0))+2*n(8,0)*m(8,0))-2*n(3,0)*m(6,0))-2*m(3,0)*n(6,0))-2*n(4,0)*m(7,0))-2*m(4,0)*n(7,0))-2*n(5,0)*m(8,0))-2*m(5,0)*n(8,0)); groebnerMatrix(3,2) = ((((((((-2*n(3,0)*n(6,0)-2*n(4,0)*n(7,0))-2*n(5,0)*n(8,0))+pow(n(3,0),2))+pow(n(4,0),2))+pow(n(5,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2)); groebnerMatrix(3,3) = (((((((((((2*a(3,0)*m(3,0)+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(6,0)*m(6,0))+2*a(7,0)*m(7,0))+2*a(8,0)*m(8,0))-2*a(3,0)*m(6,0))-2*m(3,0)*a(6,0))-2*a(4,0)*m(7,0))-2*m(4,0)*a(7,0))-2*a(5,0)*m(8,0))-2*m(5,0)*a(8,0)); groebnerMatrix(3,4) = (((((((((((2*a(3,0)*n(3,0)+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(6,0)*n(6,0))+2*a(7,0)*n(7,0))+2*a(8,0)*n(8,0))-2*a(3,0)*n(6,0))-2*n(3,0)*a(6,0))-2*a(4,0)*n(7,0))-2*n(4,0)*a(7,0))-2*a(5,0)*n(8,0))-2*n(5,0)*a(8,0)); groebnerMatrix(3,5) = (((((((((-c12w+pow(a(3,0),2))+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(6,0),2))+pow(a(7,0),2))+pow(a(8,0),2))-2*a(3,0)*a(6,0))-2*a(4,0)*a(7,0))-2*a(5,0)*a(8,0)); groebnerMatrix(4,0) = ((((((((-2*m(3,0)*m(9,0)-2*m(4,0)*m(10,0))-2*m(5,0)*m(11,0))+pow(m(3,0),2))+pow(m(4,0),2))+pow(m(5,0),2))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2)); groebnerMatrix(4,1) = (((((((((((2*n(3,0)*m(3,0)+2*n(4,0)*m(4,0))+2*n(5,0)*m(5,0))+2*n(9,0)*m(9,0))+2*n(10,0)*m(10,0))+2*n(11,0)*m(11,0))-2*n(3,0)*m(9,0))-2*m(3,0)*n(9,0))-2*n(4,0)*m(10,0))-2*m(4,0)*n(10,0))-2*n(5,0)*m(11,0))-2*m(5,0)*n(11,0)); groebnerMatrix(4,2) = ((((((((-2*n(3,0)*n(9,0)-2*n(4,0)*n(10,0))-2*n(5,0)*n(11,0))+pow(n(3,0),2))+pow(n(4,0),2))+pow(n(5,0),2))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2)); groebnerMatrix(4,3) = (((((((((((2*a(3,0)*m(3,0)+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(9,0)*m(9,0))+2*a(10,0)*m(10,0))+2*a(11,0)*m(11,0))-2*a(3,0)*m(9,0))-2*m(3,0)*a(9,0))-2*a(4,0)*m(10,0))-2*m(4,0)*a(10,0))-2*a(5,0)*m(11,0))-2*m(5,0)*a(11,0)); groebnerMatrix(4,4) = (((((((((((2*a(3,0)*n(3,0)+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(9,0)*n(9,0))+2*a(10,0)*n(10,0))+2*a(11,0)*n(11,0))-2*a(3,0)*n(9,0))-2*n(3,0)*a(9,0))-2*a(4,0)*n(10,0))-2*n(4,0)*a(10,0))-2*a(5,0)*n(11,0))-2*n(5,0)*a(11,0)); groebnerMatrix(4,5) = (((((((((-c13w+pow(a(3,0),2))+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(9,0),2))+pow(a(10,0),2))+pow(a(11,0),2))-2*a(3,0)*a(9,0))-2*a(4,0)*a(10,0))-2*a(5,0)*a(11,0)); } opengv/src/absolute_pose/modules/gpnp2/code.cpp0000664016516101651610000000562713344612246020570 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp2::compute( Eigen::Matrix & groebnerMatrix ) { sPolynomial5(groebnerMatrix); sPolynomial6(groebnerMatrix); groebnerRow5_00_f(groebnerMatrix,6); sPolynomial7(groebnerMatrix); groebnerRow5_00_f(groebnerMatrix,7); groebnerRow6_00_f(groebnerMatrix,7); sPolynomial8(groebnerMatrix); groebnerRow7_10_f(groebnerMatrix,8); groebnerRow6_00_f(groebnerMatrix,8); groebnerRow7_00_f(groebnerMatrix,8); sPolynomial9(groebnerMatrix); groebnerRow7_00_f(groebnerMatrix,9); groebnerRow8_00_f(groebnerMatrix,9); } opengv/src/absolute_pose/modules/main.cpp0000664016516101651610000006415113635643413017554 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include void opengv::absolute_pose::modules::p3p_kneip_main( const bearingVectors_t & f, const points_t & p, transformations_t & solutions ) { point_t P1 = p[0]; point_t P2 = p[1]; point_t P3 = p[2]; Eigen::Vector3d temp1 = P2 - P1; Eigen::Vector3d temp2 = P3 - P1; if( temp1.cross(temp2).norm() == 0) return; bearingVector_t f1 = f[0]; bearingVector_t f2 = f[1]; bearingVector_t f3 = f[2]; Eigen::Vector3d e1 = f1; Eigen::Vector3d e3 = f1.cross(f2); e3 = e3/e3.norm(); Eigen::Vector3d e2 = e3.cross(e1); rotation_t T; T.row(0) = e1.transpose(); T.row(1) = e2.transpose(); T.row(2) = e3.transpose(); f3 = T*f3; if( f3(2,0) > 0) { f1 = f[1]; f2 = f[0]; f3 = f[2]; e1 = f1; e3 = f1.cross(f2); e3 = e3/e3.norm(); e2 = e3.cross(e1); T.row(0) = e1.transpose(); T.row(1) = e2.transpose(); T.row(2) = e3.transpose(); f3 = T*f3; P1 = p[1]; P2 = p[0]; P3 = p[2]; } Eigen::Vector3d n1 = P2-P1; n1 = n1/n1.norm(); Eigen::Vector3d n3 = n1.cross(P3-P1); n3 = n3/n3.norm(); Eigen::Vector3d n2 = n3.cross(n1); rotation_t N; N.row(0) = n1.transpose(); N.row(1) = n2.transpose(); N.row(2) = n3.transpose(); P3 = N*(P3-P1); double d_12 = temp1.norm(); double f_1 = f3(0,0)/f3(2,0); double f_2 = f3(1,0)/f3(2,0); double p_1 = P3(0,0); double p_2 = P3(1,0); double cos_beta = f1.dot(f2); double b = 1/( 1 - pow( cos_beta, 2 ) ) - 1; if( cos_beta < 0 ) b = -sqrt(b); else b = sqrt(b); double f_1_pw2 = pow(f_1,2); double f_2_pw2 = pow(f_2,2); double p_1_pw2 = pow(p_1,2); double p_1_pw3 = p_1_pw2 * p_1; double p_1_pw4 = p_1_pw3 * p_1; double p_2_pw2 = pow(p_2,2); double p_2_pw3 = p_2_pw2 * p_2; double p_2_pw4 = p_2_pw3 * p_2; double d_12_pw2 = pow(d_12,2); double b_pw2 = pow(b,2); Eigen::Matrix factors; factors(0,0) = -f_2_pw2*p_2_pw4 -p_2_pw4*f_1_pw2 -p_2_pw4; factors(1,0) = 2*p_2_pw3*d_12*b +2*f_2_pw2*p_2_pw3*d_12*b -2*f_2*p_2_pw3*f_1*d_12; factors(2,0) = -f_2_pw2*p_2_pw2*p_1_pw2 -f_2_pw2*p_2_pw2*d_12_pw2*b_pw2 -f_2_pw2*p_2_pw2*d_12_pw2 +f_2_pw2*p_2_pw4 +p_2_pw4*f_1_pw2 +2*p_1*p_2_pw2*d_12 +2*f_1*f_2*p_1*p_2_pw2*d_12*b -p_2_pw2*p_1_pw2*f_1_pw2 +2*p_1*p_2_pw2*f_2_pw2*d_12 -p_2_pw2*d_12_pw2*b_pw2 -2*p_1_pw2*p_2_pw2; factors(3,0) = 2*p_1_pw2*p_2*d_12*b +2*f_2*p_2_pw3*f_1*d_12 -2*f_2_pw2*p_2_pw3*d_12*b -2*p_1*p_2*d_12_pw2*b; factors(4,0) = -2*f_2*p_2_pw2*f_1*p_1*d_12*b +f_2_pw2*p_2_pw2*d_12_pw2 +2*p_1_pw3*d_12 -p_1_pw2*d_12_pw2 +f_2_pw2*p_2_pw2*p_1_pw2 -p_1_pw4 -2*f_2_pw2*p_2_pw2*p_1*d_12 +p_2_pw2*f_1_pw2*p_1_pw2 +f_2_pw2*p_2_pw2*d_12_pw2*b_pw2; std::vector realRoots = math::o4_roots(factors); for( int i = 0; i < 4; i++ ) { double cot_alpha = (-f_1*p_1/f_2-realRoots[i]*p_2+d_12*b)/ (-f_1*realRoots[i]*p_2/f_2+p_1-d_12); double cos_theta = realRoots[i]; double sin_theta = sqrt(1-pow(realRoots[i],2)); double sin_alpha = sqrt(1/(pow(cot_alpha,2)+1)); double cos_alpha = sqrt(1-pow(sin_alpha,2)); if (cot_alpha < 0) cos_alpha = -cos_alpha; translation_t C; C(0,0) = d_12*cos_alpha*(sin_alpha*b+cos_alpha); C(1,0) = cos_theta*d_12*sin_alpha*(sin_alpha*b+cos_alpha); C(2,0) = sin_theta*d_12*sin_alpha*(sin_alpha*b+cos_alpha); C = P1 + N.transpose()*C; rotation_t R; R(0,0) = -cos_alpha; R(0,1) = -sin_alpha*cos_theta; R(0,2) = -sin_alpha*sin_theta; R(1,0) = sin_alpha; R(1,1) = -cos_alpha*cos_theta; R(1,2) = -cos_alpha*sin_theta; R(2,0) = 0.0; R(2,1) = -sin_theta; R(2,2) = cos_theta; R = N.transpose()*R.transpose()*T; transformation_t solution; solution.col(3) = C; solution.block<3,3>(0,0) = R; solutions.push_back(solution); } } void opengv::absolute_pose::modules::p3p_gao_main( const bearingVectors_t & f, const points_t & points, transformations_t & solutions ) { point_t A = points[0]; point_t B = points[1]; point_t C = points[2]; Eigen::Vector3d tempp; tempp = A-B; double AB = tempp.norm(); tempp = B-C; double BC = tempp.norm(); tempp = A-C; double AC = tempp.norm(); bearingVector_t f1 = f[0]; bearingVector_t f2 = f[1]; bearingVector_t f3 = f[2]; double cosalpha = f2.transpose()*f3; double cosbeta = f1.transpose()*f3; double cosgamma = f1.transpose()*f2; double a=pow((BC/AB),2); double b=pow((AC/AB),2); double p=2*cosalpha; double q=2*cosbeta; double r=2*cosgamma; double aSq = a * a; double bSq = b * b; double pSq = p*p; double qSq = q*q; double rSq = r*r; if ((pSq + qSq + rSq - p*q*r - 1) == 0) return; Eigen::Matrix factors; factors[0] = -2*b + bSq + aSq + 1 - b*rSq*a + 2*b*a - 2*a; if (factors[0] == 0) return; factors[1] = -2*b*q*a - 2*aSq*q + b*rSq*q*a - 2*q + 2*b*q + 4*a*q + p*b*r + b*r*p*a - bSq*r*p; factors[2] = qSq + bSq*rSq - b*pSq - q*p*b*r + bSq*pSq - b*rSq*a + 2 - 2*bSq - a*b*r*p*q + 2*aSq - 4*a - 2*qSq*a + qSq*aSq; factors[3] = -bSq*r*p + b*r*p*a - 2*aSq*q + q*pSq*b + 2*b*q*a + 4*a*q + p*b*r - 2*b*q - 2*q; factors[4] = 1 - 2*a + 2*b + bSq - b*pSq + aSq - 2*b*a; std::vector x_temp = math::o4_roots(factors); Eigen::Matrix x; for( size_t i = 0; i < 4; i++ ) x[i] = x_temp[i]; double temp = (pSq*(a-1+b) + p*q*r - q*a*r*p + (a-1-b)*rSq); double b0 = b * temp * temp; double rCb = rSq*r; Eigen::Matrix tempXP2; tempXP2[0] = x[0]*x[0]; tempXP2[1] = x[1]*x[1]; tempXP2[2] = x[2]*x[2]; tempXP2[3] = x[3]*x[3]; Eigen::Matrix tempXP3; tempXP3[0] = tempXP2[0]*x[0]; tempXP3[1] = tempXP2[1]*x[1]; tempXP3[2] = tempXP2[2]*x[2]; tempXP3[3] = tempXP2[3]*x[3]; Eigen::Matrix ones; for( size_t i = 0; i < 4; i++) ones[i] = 1.0; Eigen::Matrix b1_part1 = (1-a-b)*tempXP2 + (q*a-q)*x + (1 - a + b)*ones; Eigen::Matrix b1_part2 = (aSq*rCb + 2*b*rCb*a - b*rSq*rCb*a - 2*a*rCb + rCb + bSq*rCb - 2*rCb*b)*tempXP3 +(p*rSq + p*aSq*rSq - 2*b*rCb*q*a + 2*rCb*b*q - 2*rCb*q - 2*p*(a+b)*rSq + rSq*rSq*p*b + 4*a*rCb*q + b*q*a*rCb*rSq - 2*rCb*aSq*q +2*rSq*p*b*a + bSq*rSq*p - rSq*rSq*p*bSq)*tempXP2 +(rCb*qSq + rSq*rCb*bSq + r*pSq*bSq - 4*a*rCb - 2*a*rCb*qSq + rCb*qSq*aSq + 2*aSq*rCb - 2*bSq*rCb - 2*pSq*b*r + 4*p*a*rSq*q + 2*a*pSq*r*b - 2*a*rSq*q*b*p - 2*pSq*a*r + r*pSq - b*rSq*rCb*a + 2*p*rSq*b*q + r*pSq*aSq -2*p*q*rSq + 2*rCb - 2*rSq*p*aSq*q - rSq*rSq*q*b*p)*x +(4*a*rCb*q + p*rSq*qSq + 2*pSq*p*b*a - 4*p*a*rSq - 2*rCb*b*q - 2*pSq*q*r - 2*bSq*rSq*p + rSq*rSq*p*b + 2*p*aSq*rSq - 2*rCb*aSq*q - 2*pSq*p*a + pSq*p*aSq + 2*p*rSq + pSq*p + 2*b*rCb*q*a + 2*q*pSq*b*r + 4*q*a*r*pSq - 2*p*a*rSq*qSq - 2*pSq*aSq*r*q + p*aSq*rSq*qSq - 2*rCb*q - 2*pSq*p*b + pSq*p*bSq - 2*pSq*b*r*q*a)*ones; Eigen::Matrix b1; b1[0] = b1_part1[0]*b1_part2[0]; b1[1] = b1_part1[1]*b1_part2[1]; b1[2] = b1_part1[2]*b1_part2[2]; b1[3] = b1_part1[3]*b1_part2[3]; Eigen::Matrix y=b1/b0; Eigen::Matrix tempYP2; tempYP2[0] = pow(y[0],2); tempYP2[1] = pow(y[1],2); tempYP2[2] = pow(y[2],2); tempYP2[3] = pow(y[3],2); Eigen::Matrix tempXY; tempXY[0] = x[0]*y[0]; tempXY[1] = x[1]*y[1]; tempXY[2] = x[2]*y[2]; tempXY[3] = x[3]*y[3]; Eigen::Matrix v= tempXP2 + tempYP2 - r*tempXY; Eigen::Matrix Z; Z[0] = AB/sqrt(v[0]); Z[1] = AB/sqrt(v[1]); Z[2] = AB/sqrt(v[2]); Z[3] = AB/sqrt(v[3]); Eigen::Matrix X; X[0] = x[0]*Z[0]; X[1] = x[1]*Z[1]; X[2] = x[2]*Z[2]; X[3] = x[3]*Z[3]; Eigen::Matrix Y; Y[0] = y[0]*Z[0]; Y[1] = y[1]*Z[1]; Y[2] = y[2]*Z[2]; Y[3] = y[3]*Z[3]; for( int i = 0; i < 4; i++ ) { //apply arun to find the transformation points_t p_cam; p_cam.push_back(X[i]*f1); p_cam.push_back(Y[i]*f2); p_cam.push_back(Z[i]*f3); transformation_t solution = math::arun_complete(points,p_cam); solutions.push_back(solution); } } void opengv::absolute_pose::modules::gp3p_main( const Eigen::Matrix3d & f, const Eigen::Matrix3d & v, const Eigen::Matrix3d & p, transformations_t & solutions) { Eigen::Matrix groebnerMatrix = Eigen::Matrix::Zero(); gp3p::init(groebnerMatrix,f,v,p); gp3p::compute(groebnerMatrix); Eigen::Matrix M = Eigen::Matrix::Zero(); M.block<6,8>(0,0) = -groebnerMatrix.block<6,8>(36,77); M(6,0) = 1.0; M(7,6) = 1.0; Eigen::EigenSolver< Eigen::Matrix > Eig(M,true); Eigen::Matrix,8,1> D = Eig.eigenvalues(); Eigen::Matrix,8,8> V = Eig.eigenvectors(); for( int c = 0; c < V.cols(); c++ ) { std::complex eigValue = D[c]; if( eigValue.imag() < 0.0001 ) { cayley_t cayley; Eigen::Vector3d n; for(size_t i = 0; i < 3; i++) { std::complex cay = V(i+4,c)/V(7,c); cayley[2-i] = cay.real(); std::complex depth = V(i+1,c)/V(7,c); n[2-i] = depth.real(); } rotation_t rotation = math::cayley2rot(cayley); //the groebner problem was set up to find the transpose! rotation.transposeInPlace(); point_t center_cam = Eigen::Vector3d::Zero(); point_t center_world = Eigen::Vector3d::Zero(); for( size_t i = 0; i < (size_t) f.cols(); i++ ) { point_t temp = rotation*(n[i]*f.col(i)+v.col(i)); center_cam = center_cam + temp; center_world = center_world + p.col(i); } center_cam = center_cam/f.cols(); center_world = center_world/f.cols(); translation_t translation = center_world - center_cam; transformation_t transformation; transformation.block<3,3>(0,0) = rotation; transformation.col(3) = translation; solutions.push_back(transformation); } } } void opengv::absolute_pose::modules::gpnp_main( const Eigen::Matrix & a, const Eigen::Matrix & V, const points_t & c, transformation_t & transformation ) { //extracting the nullspace vectors Eigen::Matrix vec_5 = V.col(7); Eigen::Matrix vec_4 = V.col(8); Eigen::Matrix vec_3 = V.col(9); Eigen::Matrix vec_2 = V.col(10); Eigen::Matrix vec_1 = V.col(11); point_t c0 = c[0]; point_t c1 = c[0]; point_t c2 = c[0]; point_t c3 = c[0]; Eigen::Matrix solution; std::vector errors; translation_t t; translations_t ts; rotation_t R; rotations_t Rs; std::vector factors; solution = a; errors.push_back(gpnp_evaluate(solution,c,t,R)); ts.push_back(t); Rs.push_back(R); //nice, now we just need to find the right combination //let's start with trying out the linear combination of the most right //null-space vector Eigen::Matrix groebnerMatrix1 = Eigen::Matrix::Zero(); gpnp1::init(groebnerMatrix1,a,vec_1,c0,c1,c2,c3); gpnp1::compute(groebnerMatrix1); factors.push_back(-groebnerMatrix1(3,2)/groebnerMatrix1(3,1)); gpnp_optimize( a, V, c, factors ); solution = a; for(size_t i = 0; i < factors.size(); i++) solution += factors[i]*V.col(12-factors.size()+i); errors.push_back(gpnp_evaluate(solution,c,t,R)); ts.push_back(t); Rs.push_back(R); //now let's compute the solution using two nullspace vectors Eigen::Matrix groebnerMatrix2 = Eigen::Matrix::Zero(); gpnp2::init(groebnerMatrix2,a,vec_2,vec_1,c0,c1,c2,c3); gpnp2::compute(groebnerMatrix2); factors[0] = -groebnerMatrix2(8,5)/groebnerMatrix2(8,4); factors.push_back( -(groebnerMatrix2(7,4)*factors[0]+groebnerMatrix2(7,5))/ groebnerMatrix2(7,3)); gpnp_optimize( a, V, c, factors ); solution = a; for(size_t i = 0; i < factors.size(); i++) solution += factors[i]*V.col(12-factors.size()+i); errors.push_back(gpnp_evaluate(solution,c,t,R)); ts.push_back(t); Rs.push_back(R); //now let's compute the solution using three nullspace vectors Eigen::Matrix groebnerMatrix3 = Eigen::Matrix::Zero(); gpnp3::init(groebnerMatrix3,a,vec_3,vec_2,vec_1,c0,c1,c2,c3); gpnp3::compute(groebnerMatrix3); factors[0] = -groebnerMatrix3(13,17)/groebnerMatrix3(13,16); factors[1] = -(groebnerMatrix3(12,16)*factors[0]+groebnerMatrix3(12,17))/ groebnerMatrix3(12,15); factors.push_back( -(groebnerMatrix3(11,15)*factors[1]+groebnerMatrix3(11,16)*factors[0]+ groebnerMatrix3(11,17))/groebnerMatrix3(11,14)); gpnp_optimize( a, V, c, factors ); solution = a; for(size_t i = 0; i < factors.size(); i++) solution += factors[i]*V.col(12-factors.size()+i); errors.push_back(gpnp_evaluate(solution,c,t,R)); ts.push_back(t); Rs.push_back(R); //now let's compute the solution using four nullspace vectors Eigen::Matrix groebnerMatrix4 = Eigen::Matrix::Zero(); gpnp4::init(groebnerMatrix4,a,vec_4,vec_3,vec_2,vec_1,c0,c1,c2,c3); gpnp4::compute(groebnerMatrix4); factors[0] = -groebnerMatrix4(23,36)/groebnerMatrix4(23,35); factors[1] = -(groebnerMatrix4(22,35)*factors[0]+groebnerMatrix4(22,36))/ groebnerMatrix4(22,34); factors[2] = -(groebnerMatrix4(21,34)*factors[1]+groebnerMatrix4(21,35)*factors[0]+ groebnerMatrix4(21,36))/groebnerMatrix4(21,33); factors.push_back( -(groebnerMatrix4(20,33)*factors[2]+groebnerMatrix4(20,34)*factors[1]+ groebnerMatrix4(20,35)*factors[0]+groebnerMatrix4(20,36))/ groebnerMatrix4(20,32)); gpnp_optimize( a, V, c, factors ); solution = a; for(size_t i = 0; i < factors.size(); i++) solution += factors[i]*V.col(12-factors.size()+i); errors.push_back(gpnp_evaluate(solution,c,t,R)); ts.push_back(t); Rs.push_back(R); //now let's compute the solution using five nullspace vectors Eigen::Matrix groebnerMatrix5 = Eigen::Matrix::Zero(); gpnp5::init(groebnerMatrix5,a,vec_5,vec_4,vec_3,vec_2,vec_1,c0,c1,c2,c3); gpnp5::compute(groebnerMatrix5); factors[0] = -groebnerMatrix5(42,79)/groebnerMatrix5(42,78); factors[1] = -(groebnerMatrix5(41,78)*factors[0]+groebnerMatrix5(41,79))/ groebnerMatrix5(41,77); factors[2] = -(groebnerMatrix5(40,77)*factors[1]+groebnerMatrix5(40,78)*factors[0]+ groebnerMatrix5(40,79))/groebnerMatrix5(40,76); factors[3] = -(groebnerMatrix5(39,76)*factors[2]+groebnerMatrix5(39,77)*factors[1]+ groebnerMatrix5(39,78)*factors[0]+groebnerMatrix5(39,79))/ groebnerMatrix5(39,75); factors.push_back( -(groebnerMatrix5(38,75)*factors[3]+groebnerMatrix5(38,76)*factors[1]+ groebnerMatrix5(38,77)*factors[1]+groebnerMatrix5(38,78)*factors[0]+ groebnerMatrix5(38,79))/groebnerMatrix5(38,74)); gpnp_optimize( a, V, c, factors ); solution = a; for(size_t i = 0; i < factors.size(); i++) solution += factors[i]*V.col(12-factors.size()+i); errors.push_back(gpnp_evaluate(solution,c,t,R)); ts.push_back(t); Rs.push_back(R); //find best solution double smallestError = errors.at(0); int minimumIndex = 0; for( int i = 1; i < 6; i++ ) { if( errors.at(i) < smallestError ) { smallestError = errors.at(i); minimumIndex = i; } } transformation.col(3) = ts.at(minimumIndex); transformation.block<3,3>(0,0) = Rs.at(minimumIndex); } double opengv::absolute_pose::modules::gpnp_evaluate( const Eigen::Matrix & solution, const points_t & c, translation_t & t, rotation_t & R ) { points_t ccam; for(size_t i = 0; i<4; i++) ccam.push_back(solution.block<3,1>(i*3,0)); transformation_t transformation = math::arun_complete(c,ccam); t = transformation.col(3); R = transformation.block<3,3>(0,0); //transform world points into camera frame and compute the error double error = 0.0; for(size_t i = 0; i<4; i++) { point_t ccam_reprojected = R.transpose() * (c[i] - t); error += 1.0 - (ccam_reprojected.dot(ccam[i])/(ccam[i].norm()*ccam_reprojected.norm())); } return error; } namespace opengv { namespace absolute_pose { namespace modules { struct GpnpOptimizationFunctor : OptimizationFunctor { const Eigen::Matrix & _a; const Eigen::Matrix & _V; const points_t & _c; size_t _dim; GpnpOptimizationFunctor( const Eigen::Matrix & a, const Eigen::Matrix & V, const points_t & c, size_t dim ) : OptimizationFunctor(dim,6), _a(a), _V(V), _c(c), _dim(dim) {} int operator()(const VectorXd &x, VectorXd &fvec) const { assert( x.size() == _dim ); assert( (unsigned int) fvec.size() == 6); Eigen::Matrix solution = _a; for(size_t i = 0; i < _dim; i++) solution += x[i]*_V.col(12-_dim+i); points_t ccam; for(size_t i = 0; i<4; i++) ccam.push_back(solution.block<3,1>(i*3,0)); Eigen::Vector3d diffw; Eigen::Vector3d diffc; size_t index = 0; for(size_t i = 0; i<3; i++) { for(size_t j = i+1; j < 4; j++) { diffw = _c[i]-_c[j]; diffc = ccam[i]-ccam[j]; fvec[index++] = diffw.dot(diffw)-diffc.dot(diffc); } } return 0; } }; } } } void opengv::absolute_pose::modules::gpnp_optimize( const Eigen::Matrix & a, const Eigen::Matrix & V, const points_t & c, std::vector & factors ) { const int n=factors.size(); VectorXd x(n); for(size_t i = 0; i < factors.size(); i++) x[i] = factors[i]; GpnpOptimizationFunctor functor( a, V, c, factors.size() ); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 1.E10*NumTraits::epsilon(); lm.parameters.xtol = 1.E10*NumTraits::epsilon(); lm.parameters.maxfev = 1000; lm.minimize(x); for(size_t i = 0; i < factors.size(); i++) factors[i] = x[i]; } void opengv::absolute_pose::modules::upnp_fill_s( const Eigen::Vector4d & quaternion, Eigen::Matrix & s ) { s[0] = quaternion[0] * quaternion[0]; s[1] = quaternion[1] * quaternion[1]; s[2] = quaternion[2] * quaternion[2]; s[3] = quaternion[3] * quaternion[3]; s[4] = quaternion[0] * quaternion[1]; s[5] = quaternion[0] * quaternion[2]; s[6] = quaternion[0] * quaternion[3]; s[7] = quaternion[1] * quaternion[2]; s[8] = quaternion[1] * quaternion[3]; s[9] = quaternion[2] * quaternion[3]; } //we use this one if the number of correspondences is pretty low (more robust) void opengv::absolute_pose::modules::upnp_main( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, std::vector,Eigen::aligned_allocator< std::pair > > & quaternions ) { Eigen::Matrix Action; upnp::setupAction_gj( M, C, gamma, Action ); Eigen::EigenSolver< Eigen::Matrix > Eig( Action, true ); Eigen::Matrix,16,16> V = Eig.eigenvectors(); //cut the double solutions double doubleSolThreshold = 0.00000001; for( int i = 0; i < 16; i++ ) { //we decided to drop the test for imaginary part //I've noticed that when the number of points is really low, things get a little //weary with noise, and complex solutions might actually be pretty good Eigen::Vector4d quaternion; double norm = 0.0; for( int q = 0; q < 4; q++ ) { quaternion[q] = V(11+q,i).real(); norm += pow(quaternion[q],2.0); } norm = sqrt(norm); if(quaternion[0] < 0) // this here is maybe risky, what if quaternion[0] is very small norm *= -1.0; for( int q = 0; q < 4; q++ ) quaternion[q] /= norm; bool alreadyThere = false; for( size_t s = 0; s < quaternions.size(); s++ ) { Eigen::Vector4d diff = quaternion - quaternions[s].second; if( diff.norm() < doubleSolThreshold ) { alreadyThere = true; break; } } if( !alreadyThere ) { Eigen::Matrix s; upnp_fill_s(quaternion,s); Eigen::Matrix valueM = s.transpose() * M * s + C * s * 2.0; double value = valueM[0] + gamma; std::vector,Eigen::aligned_allocator< std::pair > >::iterator qidx = quaternions.begin(); while( qidx != quaternions.end() && qidx->first < value ) qidx++; quaternions.insert(qidx,std::pair(value,quaternion)); } } } //this one is the really fast, symmetric version, that we use in the normal case void opengv::absolute_pose::modules::upnp_main_sym( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, std::vector,Eigen::aligned_allocator< std::pair > > & quaternions ) { Eigen::Matrix Action; upnp::setupAction_sym_gj( M, C, gamma, Action ); Eigen::EigenSolver< Eigen::Matrix > Eig( Action, true ); Eigen::Matrix,8,8> V = Eig.eigenvectors(); //ok, let's cut the imaginary solutions (with a reasonable threshold!) // const double imagThreshold = 0.01; std::vector,Eigen::aligned_allocator< std::pair > > bad_quaternions; for( int i = 0; i < 8; i++ ) { Eigen::Vector4d quaternion; quaternion[3] = V(7,i).real(); quaternion[2] = V(6,i).real(); quaternion[1] = V(5,i).real(); quaternion[0] = V(4,i).real(); double norm = 0.0; for( int q = 0; q < 4; q++ ) norm += pow(quaternion[q],2.0); norm = sqrt(norm); for( int q = 0; q < 4; q++ ) quaternion[q] /= norm; Eigen::Matrix s; upnp_fill_s(quaternion,s); Eigen::Matrix valueM = s.transpose() * M * s + 2.0 * C * s; double value = valueM[0] + gamma; if( true )//fabs(D[i].imag()) < imagThreshold ) //use all results for the moment { std::vector,Eigen::aligned_allocator< std::pair > >::iterator qidx = quaternions.begin(); while( qidx != quaternions.end() && qidx->first < value ) qidx++; quaternions.insert(qidx,std::pair(value,quaternion)); } else { std::vector,Eigen::aligned_allocator< std::pair > >::iterator qidx = bad_quaternions.begin(); while( qidx != bad_quaternions.end() && qidx->first < value ) qidx++; bad_quaternions.insert(qidx,std::pair(value,quaternion)); } } if( quaternions.size() == 0 ) quaternions = bad_quaternions; } opengv/src/absolute_pose/modules/upnp4.cpp0000664016516101651610000020272613344612246017675 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include void opengv::absolute_pose::modules::upnp::setupAction_sym_gj( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, Eigen::Matrix & Action ) { Eigen::Matrix M1 = Eigen::Matrix::Zero(); M1(0,0) = 4*M(0,0); M1(0,1) = 4*M(4,0)+2*M(0,4); M1(0,2) = 2*M(4,4)+4*M(1,0); M1(0,3) = 2*M(1,4); M1(0,4) = 4*M(5,0)+2*M(0,5); M1(0,5) = 4*M(7,0)+2*M(5,4)+2*M(4,5); M1(0,6) = 2*M(7,4)+2*M(1,5); M1(0,7) = 2*M(5,5)+4*M(2,0); M1(0,8) = 2*M(7,5)+2*M(2,4); M1(0,9) = 2*M(2,5); M1(0,10) = 4*M(6,0)+2*M(0,6); M1(0,11) = 4*M(8,0)+2*M(6,4)+2*M(4,6); M1(0,12) = 2*M(8,4)+2*M(1,6); M1(0,13) = 4*M(9,0)+2*M(6,5)+2*M(5,6); M1(0,14) = 2*M(9,4)+2*M(8,5)+2*M(7,6); M1(0,15) = 2*M(9,5)+2*M(2,6); M1(0,16) = 2*M(6,6)+4*M(3,0); M1(0,17) = 2*M(8,6)+2*M(3,4); M1(0,18) = 2*M(9,6)+2*M(3,5); M1(0,19) = 2*M(3,6); M1(0,20) = 4*C(0,0); M1(0,21) = 2*C(0,4); M1(0,22) = 2*C(0,5); M1(0,23) = 2*C(0,6); M1(1,0) = 2*M(0,4); M1(1,1) = 2*M(4,4)+4*M(0,1); M1(1,2) = 4*M(4,1)+2*M(1,4); M1(1,3) = 4*M(1,1); M1(1,4) = 2*M(5,4)+2*M(0,7); M1(1,5) = 2*M(7,4)+4*M(5,1)+2*M(4,7); M1(1,6) = 4*M(7,1)+2*M(1,7); M1(1,7) = 2*M(5,7)+2*M(2,4); M1(1,8) = 2*M(7,7)+4*M(2,1); M1(1,9) = 2*M(2,7); M1(1,10) = 2*M(6,4)+2*M(0,8); M1(1,11) = 2*M(8,4)+4*M(6,1)+2*M(4,8); M1(1,12) = 4*M(8,1)+2*M(1,8); M1(1,13) = 2*M(9,4)+2*M(6,7)+2*M(5,8); M1(1,14) = 4*M(9,1)+2*M(8,7)+2*M(7,8); M1(1,15) = 2*M(9,7)+2*M(2,8); M1(1,16) = 2*M(6,8)+2*M(3,4); M1(1,17) = 2*M(8,8)+4*M(3,1); M1(1,18) = 2*M(9,8)+2*M(3,7); M1(1,19) = 2*M(3,8); M1(1,20) = 2*C(0,4); M1(1,21) = 4*C(0,1); M1(1,22) = 2*C(0,7); M1(1,23) = 2*C(0,8); M1(2,0) = 2*M(0,5); M1(2,1) = 2*M(4,5)+2*M(0,7); M1(2,2) = 2*M(4,7)+2*M(1,5); M1(2,3) = 2*M(1,7); M1(2,4) = 2*M(5,5)+4*M(0,2); M1(2,5) = 2*M(7,5)+2*M(5,7)+4*M(4,2); M1(2,6) = 2*M(7,7)+4*M(1,2); M1(2,7) = 4*M(5,2)+2*M(2,5); M1(2,8) = 4*M(7,2)+2*M(2,7); M1(2,9) = 4*M(2,2); M1(2,10) = 2*M(6,5)+2*M(0,9); M1(2,11) = 2*M(8,5)+2*M(6,7)+2*M(4,9); M1(2,12) = 2*M(8,7)+2*M(1,9); M1(2,13) = 2*M(9,5)+4*M(6,2)+2*M(5,9); M1(2,14) = 2*M(9,7)+4*M(8,2)+2*M(7,9); M1(2,15) = 4*M(9,2)+2*M(2,9); M1(2,16) = 2*M(6,9)+2*M(3,5); M1(2,17) = 2*M(8,9)+2*M(3,7); M1(2,18) = 2*M(9,9)+4*M(3,2); M1(2,19) = 2*M(3,9); M1(2,20) = 2*C(0,5); M1(2,21) = 2*C(0,7); M1(2,22) = 4*C(0,2); M1(2,23) = 2*C(0,9); M1(3,0) = 2*M(0,6); M1(3,1) = 2*M(4,6)+2*M(0,8); M1(3,2) = 2*M(4,8)+2*M(1,6); M1(3,3) = 2*M(1,8); M1(3,4) = 2*M(5,6)+2*M(0,9); M1(3,5) = 2*M(7,6)+2*M(5,8)+2*M(4,9); M1(3,6) = 2*M(7,8)+2*M(1,9); M1(3,7) = 2*M(5,9)+2*M(2,6); M1(3,8) = 2*M(7,9)+2*M(2,8); M1(3,9) = 2*M(2,9); M1(3,10) = 2*M(6,6)+4*M(0,3); M1(3,11) = 2*M(8,6)+2*M(6,8)+4*M(4,3); M1(3,12) = 2*M(8,8)+4*M(1,3); M1(3,13) = 2*M(9,6)+2*M(6,9)+4*M(5,3); M1(3,14) = 2*M(9,8)+2*M(8,9)+4*M(7,3); M1(3,15) = 2*M(9,9)+4*M(2,3); M1(3,16) = 4*M(6,3)+2*M(3,6); M1(3,17) = 4*M(8,3)+2*M(3,8); M1(3,18) = 4*M(9,3)+2*M(3,9); M1(3,19) = 4*M(3,3); M1(3,20) = 2*C(0,6); M1(3,21) = 2*C(0,8); M1(3,22) = 2*C(0,9); M1(3,23) = 4*C(0,3); M1(4,0) = 1; M1(4,2) = 1; M1(4,7) = 1; M1(4,16) = 1; M1(4,20) = -1; M1(5,1) = 1; M1(5,3) = 1; M1(5,8) = 1; M1(5,17) = 1; M1(5,21) = -1; M1(6,4) = 1; M1(6,6) = 1; M1(6,9) = 1; M1(6,18) = 1; M1(6,22) = -1; M1(7,10) = 1; M1(7,12) = 1; M1(7,15) = 1; M1(7,19) = 1; M1(7,23) = -1; Eigen::Matrix M1_part1 = M1.block<7,7>(0,0); Eigen::Matrix M1_part2 = M1_part1.inverse() * M1.block<7,24>(0,0); M1.block<7,24>(0,0) = M1_part2; //Some more cancellation in column 10 for( int i = 6; i >= 0; i-- ) { double factor = M1(i,10)/M1(7,10); M1.row(i) -= factor * M1.row(7); } std::vector*> M2; for( int r = 0; r < 141; r++ ) { std::vector * row = new std::vector(); for( int c = 0; c < 149; c++ ) row->push_back(0.0); M2.push_back(row); } (*(M2[0]))[32] = M1(3,3); (*(M2[0]))[38] = M1(3,7); (*(M2[0]))[39] = M1(3,8); (*(M2[0]))[41] = M1(3,9); (*(M2[0]))[49] = M1(3,11); (*(M2[0]))[50] = M1(3,12); (*(M2[0]))[52] = M1(3,13); (*(M2[0]))[53] = M1(3,14); (*(M2[0]))[55] = M1(3,15); (*(M2[0]))[61] = M1(3,16); (*(M2[0]))[62] = M1(3,17); (*(M2[0]))[64] = M1(3,18); (*(M2[0]))[69] = M1(3,19); (*(M2[0]))[96] = M1(3,20); (*(M2[0]))[97] = M1(3,21); (*(M2[0]))[100] = M1(3,22); (*(M2[0]))[110] = M1(3,23); (*(M2[1]))[35] = M1(5,5); (*(M2[1]))[38] = M1(5,7); (*(M2[1]))[39] = M1(5,8); (*(M2[1]))[41] = M1(5,9); (*(M2[1]))[49] = M1(5,11); (*(M2[1]))[50] = M1(5,12); (*(M2[1]))[52] = M1(5,13); (*(M2[1]))[53] = M1(5,14); (*(M2[1]))[55] = M1(5,15); (*(M2[1]))[61] = M1(5,16); (*(M2[1]))[62] = M1(5,17); (*(M2[1]))[64] = M1(5,18); (*(M2[1]))[69] = M1(5,19); (*(M2[1]))[96] = M1(5,20); (*(M2[1]))[97] = M1(5,21); (*(M2[1]))[100] = M1(5,22); (*(M2[1]))[110] = M1(5,23); (*(M2[2]))[36] = M1(6,6); (*(M2[2]))[38] = M1(6,7); (*(M2[2]))[39] = M1(6,8); (*(M2[2]))[41] = M1(6,9); (*(M2[2]))[49] = M1(6,11); (*(M2[2]))[50] = M1(6,12); (*(M2[2]))[52] = M1(6,13); (*(M2[2]))[53] = M1(6,14); (*(M2[2]))[55] = M1(6,15); (*(M2[2]))[61] = M1(6,16); (*(M2[2]))[62] = M1(6,17); (*(M2[2]))[64] = M1(6,18); (*(M2[2]))[69] = M1(6,19); (*(M2[2]))[96] = M1(6,20); (*(M2[2]))[97] = M1(6,21); (*(M2[2]))[100] = M1(6,22); (*(M2[2]))[110] = M1(6,23); (*(M2[3]))[48] = M1(7,10); (*(M2[3]))[50] = M1(7,12); (*(M2[3]))[55] = M1(7,15); (*(M2[3]))[69] = M1(7,19); (*(M2[3]))[110] = M1(7,23); (*(M2[4]))[12] = M1(2,2); (*(M2[4]))[19] = M1(2,7); (*(M2[4]))[20] = M1(2,8); (*(M2[4]))[22] = M1(2,9); (*(M2[4]))[35] = M1(2,11); (*(M2[4]))[36] = M1(2,12); (*(M2[4]))[38] = M1(2,13); (*(M2[4]))[39] = M1(2,14); (*(M2[4]))[41] = M1(2,15); (*(M2[4]))[52] = M1(2,16); (*(M2[4]))[53] = M1(2,17); (*(M2[4]))[55] = M1(2,18); (*(M2[4]))[64] = M1(2,19); (*(M2[4]))[81] = M1(2,20); (*(M2[4]))[82] = M1(2,21); (*(M2[4]))[85] = M1(2,22); (*(M2[4]))[100] = M1(2,23); (*(M2[5]))[13] = M1(3,3); (*(M2[5]))[19] = M1(3,7); (*(M2[5]))[20] = M1(3,8); (*(M2[5]))[22] = M1(3,9); (*(M2[5]))[35] = M1(3,11); (*(M2[5]))[36] = M1(3,12); (*(M2[5]))[38] = M1(3,13); (*(M2[5]))[39] = M1(3,14); (*(M2[5]))[41] = M1(3,15); (*(M2[5]))[52] = M1(3,16); (*(M2[5]))[53] = M1(3,17); (*(M2[5]))[55] = M1(3,18); (*(M2[5]))[64] = M1(3,19); (*(M2[5]))[81] = M1(3,20); (*(M2[5]))[82] = M1(3,21); (*(M2[5]))[85] = M1(3,22); (*(M2[5]))[100] = M1(3,23); (*(M2[6]))[15] = M1(4,4); (*(M2[6]))[19] = M1(4,7); (*(M2[6]))[20] = M1(4,8); (*(M2[6]))[22] = M1(4,9); (*(M2[6]))[35] = M1(4,11); (*(M2[6]))[36] = M1(4,12); (*(M2[6]))[38] = M1(4,13); (*(M2[6]))[39] = M1(4,14); (*(M2[6]))[41] = M1(4,15); (*(M2[6]))[52] = M1(4,16); (*(M2[6]))[53] = M1(4,17); (*(M2[6]))[55] = M1(4,18); (*(M2[6]))[64] = M1(4,19); (*(M2[6]))[81] = M1(4,20); (*(M2[6]))[82] = M1(4,21); (*(M2[6]))[85] = M1(4,22); (*(M2[6]))[100] = M1(4,23); (*(M2[7]))[16] = M1(5,5); (*(M2[7]))[19] = M1(5,7); (*(M2[7]))[20] = M1(5,8); (*(M2[7]))[22] = M1(5,9); (*(M2[7]))[35] = M1(5,11); (*(M2[7]))[36] = M1(5,12); (*(M2[7]))[38] = M1(5,13); (*(M2[7]))[39] = M1(5,14); (*(M2[7]))[41] = M1(5,15); (*(M2[7]))[52] = M1(5,16); (*(M2[7]))[53] = M1(5,17); (*(M2[7]))[55] = M1(5,18); (*(M2[7]))[64] = M1(5,19); (*(M2[7]))[81] = M1(5,20); (*(M2[7]))[82] = M1(5,21); (*(M2[7]))[85] = M1(5,22); (*(M2[7]))[100] = M1(5,23); (*(M2[8]))[17] = M1(6,6); (*(M2[8]))[19] = M1(6,7); (*(M2[8]))[20] = M1(6,8); (*(M2[8]))[22] = M1(6,9); (*(M2[8]))[35] = M1(6,11); (*(M2[8]))[36] = M1(6,12); (*(M2[8]))[38] = M1(6,13); (*(M2[8]))[39] = M1(6,14); (*(M2[8]))[41] = M1(6,15); (*(M2[8]))[52] = M1(6,16); (*(M2[8]))[53] = M1(6,17); (*(M2[8]))[55] = M1(6,18); (*(M2[8]))[64] = M1(6,19); (*(M2[8]))[81] = M1(6,20); (*(M2[8]))[82] = M1(6,21); (*(M2[8]))[85] = M1(6,22); (*(M2[8]))[100] = M1(6,23); (*(M2[9]))[34] = M1(7,10); (*(M2[9]))[36] = M1(7,12); (*(M2[9]))[41] = M1(7,15); (*(M2[9]))[64] = M1(7,19); (*(M2[9]))[100] = M1(7,23); (*(M2[10]))[26] = M1(2,2); (*(M2[10]))[35] = M1(2,7); (*(M2[10]))[36] = M1(2,8); (*(M2[10]))[39] = M1(2,9); (*(M2[10]))[45] = M1(2,11); (*(M2[10]))[46] = M1(2,12); (*(M2[10]))[49] = M1(2,13); (*(M2[10]))[50] = M1(2,14); (*(M2[10]))[53] = M1(2,15); (*(M2[10]))[58] = M1(2,16); (*(M2[10]))[59] = M1(2,17); (*(M2[10]))[62] = M1(2,18); (*(M2[10]))[67] = M1(2,19); (*(M2[10]))[92] = M1(2,20); (*(M2[10]))[93] = M1(2,21); (*(M2[10]))[97] = M1(2,22); (*(M2[10]))[107] = M1(2,23); (*(M2[11]))[27] = M1(3,3); (*(M2[11]))[35] = M1(3,7); (*(M2[11]))[36] = M1(3,8); (*(M2[11]))[39] = M1(3,9); (*(M2[11]))[45] = M1(3,11); (*(M2[11]))[46] = M1(3,12); (*(M2[11]))[49] = M1(3,13); (*(M2[11]))[50] = M1(3,14); (*(M2[11]))[53] = M1(3,15); (*(M2[11]))[58] = M1(3,16); (*(M2[11]))[59] = M1(3,17); (*(M2[11]))[62] = M1(3,18); (*(M2[11]))[67] = M1(3,19); (*(M2[11]))[92] = M1(3,20); (*(M2[11]))[93] = M1(3,21); (*(M2[11]))[97] = M1(3,22); (*(M2[11]))[107] = M1(3,23); (*(M2[12]))[31] = M1(5,5); (*(M2[12]))[35] = M1(5,7); (*(M2[12]))[36] = M1(5,8); (*(M2[12]))[39] = M1(5,9); (*(M2[12]))[45] = M1(5,11); (*(M2[12]))[46] = M1(5,12); (*(M2[12]))[49] = M1(5,13); (*(M2[12]))[50] = M1(5,14); (*(M2[12]))[53] = M1(5,15); (*(M2[12]))[58] = M1(5,16); (*(M2[12]))[59] = M1(5,17); (*(M2[12]))[62] = M1(5,18); (*(M2[12]))[67] = M1(5,19); (*(M2[12]))[92] = M1(5,20); (*(M2[12]))[93] = M1(5,21); (*(M2[12]))[97] = M1(5,22); (*(M2[12]))[107] = M1(5,23); (*(M2[13]))[32] = M1(6,6); (*(M2[13]))[35] = M1(6,7); (*(M2[13]))[36] = M1(6,8); (*(M2[13]))[39] = M1(6,9); (*(M2[13]))[45] = M1(6,11); (*(M2[13]))[46] = M1(6,12); (*(M2[13]))[49] = M1(6,13); (*(M2[13]))[50] = M1(6,14); (*(M2[13]))[53] = M1(6,15); (*(M2[13]))[58] = M1(6,16); (*(M2[13]))[59] = M1(6,17); (*(M2[13]))[62] = M1(6,18); (*(M2[13]))[67] = M1(6,19); (*(M2[13]))[92] = M1(6,20); (*(M2[13]))[93] = M1(6,21); (*(M2[13]))[97] = M1(6,22); (*(M2[13]))[107] = M1(6,23); (*(M2[14]))[44] = M1(7,10); (*(M2[14]))[46] = M1(7,12); (*(M2[14]))[53] = M1(7,15); (*(M2[14]))[67] = M1(7,19); (*(M2[14]))[107] = M1(7,23); (*(M2[15]))[7] = M1(2,2); (*(M2[15]))[16] = M1(2,7); (*(M2[15]))[17] = M1(2,8); (*(M2[15]))[20] = M1(2,9); (*(M2[15]))[31] = M1(2,11); (*(M2[15]))[32] = M1(2,12); (*(M2[15]))[35] = M1(2,13); (*(M2[15]))[36] = M1(2,14); (*(M2[15]))[39] = M1(2,15); (*(M2[15]))[49] = M1(2,16); (*(M2[15]))[50] = M1(2,17); (*(M2[15]))[53] = M1(2,18); (*(M2[15]))[62] = M1(2,19); (*(M2[15]))[77] = M1(2,20); (*(M2[15]))[78] = M1(2,21); (*(M2[15]))[82] = M1(2,22); (*(M2[15]))[97] = M1(2,23); (*(M2[16]))[8] = M1(3,3); (*(M2[16]))[16] = M1(3,7); (*(M2[16]))[17] = M1(3,8); (*(M2[16]))[20] = M1(3,9); (*(M2[16]))[31] = M1(3,11); (*(M2[16]))[32] = M1(3,12); (*(M2[16]))[35] = M1(3,13); (*(M2[16]))[36] = M1(3,14); (*(M2[16]))[39] = M1(3,15); (*(M2[16]))[49] = M1(3,16); (*(M2[16]))[50] = M1(3,17); (*(M2[16]))[53] = M1(3,18); (*(M2[16]))[62] = M1(3,19); (*(M2[16]))[77] = M1(3,20); (*(M2[16]))[78] = M1(3,21); (*(M2[16]))[82] = M1(3,22); (*(M2[16]))[97] = M1(3,23); (*(M2[17]))[11] = M1(4,4); (*(M2[17]))[16] = M1(4,7); (*(M2[17]))[17] = M1(4,8); (*(M2[17]))[20] = M1(4,9); (*(M2[17]))[31] = M1(4,11); (*(M2[17]))[32] = M1(4,12); (*(M2[17]))[35] = M1(4,13); (*(M2[17]))[36] = M1(4,14); (*(M2[17]))[39] = M1(4,15); (*(M2[17]))[49] = M1(4,16); (*(M2[17]))[50] = M1(4,17); (*(M2[17]))[53] = M1(4,18); (*(M2[17]))[62] = M1(4,19); (*(M2[17]))[77] = M1(4,20); (*(M2[17]))[78] = M1(4,21); (*(M2[17]))[82] = M1(4,22); (*(M2[17]))[97] = M1(4,23); (*(M2[18]))[12] = M1(5,5); (*(M2[18]))[16] = M1(5,7); (*(M2[18]))[17] = M1(5,8); (*(M2[18]))[20] = M1(5,9); (*(M2[18]))[31] = M1(5,11); (*(M2[18]))[32] = M1(5,12); (*(M2[18]))[35] = M1(5,13); (*(M2[18]))[36] = M1(5,14); (*(M2[18]))[39] = M1(5,15); (*(M2[18]))[49] = M1(5,16); (*(M2[18]))[50] = M1(5,17); (*(M2[18]))[53] = M1(5,18); (*(M2[18]))[62] = M1(5,19); (*(M2[18]))[77] = M1(5,20); (*(M2[18]))[78] = M1(5,21); (*(M2[18]))[82] = M1(5,22); (*(M2[18]))[97] = M1(5,23); (*(M2[19]))[13] = M1(6,6); (*(M2[19]))[16] = M1(6,7); (*(M2[19]))[17] = M1(6,8); (*(M2[19]))[20] = M1(6,9); (*(M2[19]))[31] = M1(6,11); (*(M2[19]))[32] = M1(6,12); (*(M2[19]))[35] = M1(6,13); (*(M2[19]))[36] = M1(6,14); (*(M2[19]))[39] = M1(6,15); (*(M2[19]))[49] = M1(6,16); (*(M2[19]))[50] = M1(6,17); (*(M2[19]))[53] = M1(6,18); (*(M2[19]))[62] = M1(6,19); (*(M2[19]))[77] = M1(6,20); (*(M2[19]))[78] = M1(6,21); (*(M2[19]))[82] = M1(6,22); (*(M2[19]))[97] = M1(6,23); (*(M2[20]))[30] = M1(7,10); (*(M2[20]))[32] = M1(7,12); (*(M2[20]))[39] = M1(7,15); (*(M2[20]))[62] = M1(7,19); (*(M2[20]))[97] = M1(7,23); (*(M2[21]))[2] = M1(1,1); (*(M2[21]))[12] = M1(1,7); (*(M2[21]))[13] = M1(1,8); (*(M2[21]))[17] = M1(1,9); (*(M2[21]))[26] = M1(1,11); (*(M2[21]))[27] = M1(1,12); (*(M2[21]))[31] = M1(1,13); (*(M2[21]))[32] = M1(1,14); (*(M2[21]))[36] = M1(1,15); (*(M2[21]))[45] = M1(1,16); (*(M2[21]))[46] = M1(1,17); (*(M2[21]))[50] = M1(1,18); (*(M2[21]))[59] = M1(1,19); (*(M2[21]))[73] = M1(1,20); (*(M2[21]))[74] = M1(1,21); (*(M2[21]))[78] = M1(1,22); (*(M2[21]))[93] = M1(1,23); (*(M2[22]))[3] = M1(2,2); (*(M2[22]))[12] = M1(2,7); (*(M2[22]))[13] = M1(2,8); (*(M2[22]))[17] = M1(2,9); (*(M2[22]))[26] = M1(2,11); (*(M2[22]))[27] = M1(2,12); (*(M2[22]))[31] = M1(2,13); (*(M2[22]))[32] = M1(2,14); (*(M2[22]))[36] = M1(2,15); (*(M2[22]))[45] = M1(2,16); (*(M2[22]))[46] = M1(2,17); (*(M2[22]))[50] = M1(2,18); (*(M2[22]))[59] = M1(2,19); (*(M2[22]))[73] = M1(2,20); (*(M2[22]))[74] = M1(2,21); (*(M2[22]))[78] = M1(2,22); (*(M2[22]))[93] = M1(2,23); (*(M2[23]))[6] = M1(4,4); (*(M2[23]))[12] = M1(4,7); (*(M2[23]))[13] = M1(4,8); (*(M2[23]))[17] = M1(4,9); (*(M2[23]))[26] = M1(4,11); (*(M2[23]))[27] = M1(4,12); (*(M2[23]))[31] = M1(4,13); (*(M2[23]))[32] = M1(4,14); (*(M2[23]))[36] = M1(4,15); (*(M2[23]))[45] = M1(4,16); (*(M2[23]))[46] = M1(4,17); (*(M2[23]))[50] = M1(4,18); (*(M2[23]))[59] = M1(4,19); (*(M2[23]))[73] = M1(4,20); (*(M2[23]))[74] = M1(4,21); (*(M2[23]))[78] = M1(4,22); (*(M2[23]))[93] = M1(4,23); (*(M2[24]))[7] = M1(5,5); (*(M2[24]))[12] = M1(5,7); (*(M2[24]))[13] = M1(5,8); (*(M2[24]))[17] = M1(5,9); (*(M2[24]))[26] = M1(5,11); (*(M2[24]))[27] = M1(5,12); (*(M2[24]))[31] = M1(5,13); (*(M2[24]))[32] = M1(5,14); (*(M2[24]))[36] = M1(5,15); (*(M2[24]))[45] = M1(5,16); (*(M2[24]))[46] = M1(5,17); (*(M2[24]))[50] = M1(5,18); (*(M2[24]))[59] = M1(5,19); (*(M2[24]))[73] = M1(5,20); (*(M2[24]))[74] = M1(5,21); (*(M2[24]))[78] = M1(5,22); (*(M2[24]))[93] = M1(5,23); (*(M2[25]))[8] = M1(6,6); (*(M2[25]))[12] = M1(6,7); (*(M2[25]))[13] = M1(6,8); (*(M2[25]))[17] = M1(6,9); (*(M2[25]))[26] = M1(6,11); (*(M2[25]))[27] = M1(6,12); (*(M2[25]))[31] = M1(6,13); (*(M2[25]))[32] = M1(6,14); (*(M2[25]))[36] = M1(6,15); (*(M2[25]))[45] = M1(6,16); (*(M2[25]))[46] = M1(6,17); (*(M2[25]))[50] = M1(6,18); (*(M2[25]))[59] = M1(6,19); (*(M2[25]))[73] = M1(6,20); (*(M2[25]))[74] = M1(6,21); (*(M2[25]))[78] = M1(6,22); (*(M2[25]))[93] = M1(6,23); (*(M2[26]))[25] = M1(7,10); (*(M2[26]))[27] = M1(7,12); (*(M2[26]))[36] = M1(7,15); (*(M2[26]))[59] = M1(7,19); (*(M2[26]))[93] = M1(7,23); (*(M2[27]))[30] = M1(2,2); (*(M2[27]))[37] = M1(2,7); (*(M2[27]))[38] = M1(2,8); (*(M2[27]))[40] = M1(2,9); (*(M2[27]))[48] = M1(2,11); (*(M2[27]))[49] = M1(2,12); (*(M2[27]))[51] = M1(2,13); (*(M2[27]))[52] = M1(2,14); (*(M2[27]))[54] = M1(2,15); (*(M2[27]))[60] = M1(2,16); (*(M2[27]))[61] = M1(2,17); (*(M2[27]))[63] = M1(2,18); (*(M2[27]))[68] = M1(2,19); (*(M2[27]))[95] = M1(2,20); (*(M2[27]))[96] = M1(2,21); (*(M2[27]))[99] = M1(2,22); (*(M2[27]))[109] = M1(2,23); (*(M2[28]))[31] = M1(3,3); (*(M2[28]))[37] = M1(3,7); (*(M2[28]))[38] = M1(3,8); (*(M2[28]))[40] = M1(3,9); (*(M2[28]))[48] = M1(3,11); (*(M2[28]))[49] = M1(3,12); (*(M2[28]))[51] = M1(3,13); (*(M2[28]))[52] = M1(3,14); (*(M2[28]))[54] = M1(3,15); (*(M2[28]))[60] = M1(3,16); (*(M2[28]))[61] = M1(3,17); (*(M2[28]))[63] = M1(3,18); (*(M2[28]))[68] = M1(3,19); (*(M2[28]))[95] = M1(3,20); (*(M2[28]))[96] = M1(3,21); (*(M2[28]))[99] = M1(3,22); (*(M2[28]))[109] = M1(3,23); (*(M2[29]))[34] = M1(5,5); (*(M2[29]))[37] = M1(5,7); (*(M2[29]))[38] = M1(5,8); (*(M2[29]))[40] = M1(5,9); (*(M2[29]))[48] = M1(5,11); (*(M2[29]))[49] = M1(5,12); (*(M2[29]))[51] = M1(5,13); (*(M2[29]))[52] = M1(5,14); (*(M2[29]))[54] = M1(5,15); (*(M2[29]))[60] = M1(5,16); (*(M2[29]))[61] = M1(5,17); (*(M2[29]))[63] = M1(5,18); (*(M2[29]))[68] = M1(5,19); (*(M2[29]))[95] = M1(5,20); (*(M2[29]))[96] = M1(5,21); (*(M2[29]))[99] = M1(5,22); (*(M2[29]))[109] = M1(5,23); (*(M2[30]))[35] = M1(6,6); (*(M2[30]))[37] = M1(6,7); (*(M2[30]))[38] = M1(6,8); (*(M2[30]))[40] = M1(6,9); (*(M2[30]))[48] = M1(6,11); (*(M2[30]))[49] = M1(6,12); (*(M2[30]))[51] = M1(6,13); (*(M2[30]))[52] = M1(6,14); (*(M2[30]))[54] = M1(6,15); (*(M2[30]))[60] = M1(6,16); (*(M2[30]))[61] = M1(6,17); (*(M2[30]))[63] = M1(6,18); (*(M2[30]))[68] = M1(6,19); (*(M2[30]))[95] = M1(6,20); (*(M2[30]))[96] = M1(6,21); (*(M2[30]))[99] = M1(6,22); (*(M2[30]))[109] = M1(6,23); (*(M2[31]))[47] = M1(7,10); (*(M2[31]))[49] = M1(7,12); (*(M2[31]))[54] = M1(7,15); (*(M2[31]))[68] = M1(7,19); (*(M2[31]))[109] = M1(7,23); (*(M2[32]))[11] = M1(2,2); (*(M2[32]))[18] = M1(2,7); (*(M2[32]))[19] = M1(2,8); (*(M2[32]))[21] = M1(2,9); (*(M2[32]))[34] = M1(2,11); (*(M2[32]))[35] = M1(2,12); (*(M2[32]))[37] = M1(2,13); (*(M2[32]))[38] = M1(2,14); (*(M2[32]))[40] = M1(2,15); (*(M2[32]))[51] = M1(2,16); (*(M2[32]))[52] = M1(2,17); (*(M2[32]))[54] = M1(2,18); (*(M2[32]))[63] = M1(2,19); (*(M2[32]))[80] = M1(2,20); (*(M2[32]))[81] = M1(2,21); (*(M2[32]))[84] = M1(2,22); (*(M2[32]))[99] = M1(2,23); (*(M2[33]))[12] = M1(3,3); (*(M2[33]))[18] = M1(3,7); (*(M2[33]))[19] = M1(3,8); (*(M2[33]))[21] = M1(3,9); (*(M2[33]))[34] = M1(3,11); (*(M2[33]))[35] = M1(3,12); (*(M2[33]))[37] = M1(3,13); (*(M2[33]))[38] = M1(3,14); (*(M2[33]))[40] = M1(3,15); (*(M2[33]))[51] = M1(3,16); (*(M2[33]))[52] = M1(3,17); (*(M2[33]))[54] = M1(3,18); (*(M2[33]))[63] = M1(3,19); (*(M2[33]))[80] = M1(3,20); (*(M2[33]))[81] = M1(3,21); (*(M2[33]))[84] = M1(3,22); (*(M2[33]))[99] = M1(3,23); (*(M2[34]))[14] = M1(4,4); (*(M2[34]))[18] = M1(4,7); (*(M2[34]))[19] = M1(4,8); (*(M2[34]))[21] = M1(4,9); (*(M2[34]))[34] = M1(4,11); (*(M2[34]))[35] = M1(4,12); (*(M2[34]))[37] = M1(4,13); (*(M2[34]))[38] = M1(4,14); (*(M2[34]))[40] = M1(4,15); (*(M2[34]))[51] = M1(4,16); (*(M2[34]))[52] = M1(4,17); (*(M2[34]))[54] = M1(4,18); (*(M2[34]))[63] = M1(4,19); (*(M2[34]))[80] = M1(4,20); (*(M2[34]))[81] = M1(4,21); (*(M2[34]))[84] = M1(4,22); (*(M2[34]))[99] = M1(4,23); (*(M2[35]))[15] = M1(5,5); (*(M2[35]))[18] = M1(5,7); (*(M2[35]))[19] = M1(5,8); (*(M2[35]))[21] = M1(5,9); (*(M2[35]))[34] = M1(5,11); (*(M2[35]))[35] = M1(5,12); (*(M2[35]))[37] = M1(5,13); (*(M2[35]))[38] = M1(5,14); (*(M2[35]))[40] = M1(5,15); (*(M2[35]))[51] = M1(5,16); (*(M2[35]))[52] = M1(5,17); (*(M2[35]))[54] = M1(5,18); (*(M2[35]))[63] = M1(5,19); (*(M2[35]))[80] = M1(5,20); (*(M2[35]))[81] = M1(5,21); (*(M2[35]))[84] = M1(5,22); (*(M2[35]))[99] = M1(5,23); (*(M2[36]))[16] = M1(6,6); (*(M2[36]))[18] = M1(6,7); (*(M2[36]))[19] = M1(6,8); (*(M2[36]))[21] = M1(6,9); (*(M2[36]))[34] = M1(6,11); (*(M2[36]))[35] = M1(6,12); (*(M2[36]))[37] = M1(6,13); (*(M2[36]))[38] = M1(6,14); (*(M2[36]))[40] = M1(6,15); (*(M2[36]))[51] = M1(6,16); (*(M2[36]))[52] = M1(6,17); (*(M2[36]))[54] = M1(6,18); (*(M2[36]))[63] = M1(6,19); (*(M2[36]))[80] = M1(6,20); (*(M2[36]))[81] = M1(6,21); (*(M2[36]))[84] = M1(6,22); (*(M2[36]))[99] = M1(6,23); (*(M2[37]))[33] = M1(7,10); (*(M2[37]))[35] = M1(7,12); (*(M2[37]))[40] = M1(7,15); (*(M2[37]))[63] = M1(7,19); (*(M2[37]))[99] = M1(7,23); (*(M2[38]))[25] = M1(2,2); (*(M2[38]))[34] = M1(2,7); (*(M2[38]))[35] = M1(2,8); (*(M2[38]))[38] = M1(2,9); (*(M2[38]))[44] = M1(2,11); (*(M2[38]))[45] = M1(2,12); (*(M2[38]))[48] = M1(2,13); (*(M2[38]))[49] = M1(2,14); (*(M2[38]))[52] = M1(2,15); (*(M2[38]))[57] = M1(2,16); (*(M2[38]))[58] = M1(2,17); (*(M2[38]))[61] = M1(2,18); (*(M2[38]))[66] = M1(2,19); (*(M2[38]))[91] = M1(2,20); (*(M2[38]))[92] = M1(2,21); (*(M2[38]))[96] = M1(2,22); (*(M2[38]))[106] = M1(2,23); (*(M2[39]))[26] = M1(3,3); (*(M2[39]))[34] = M1(3,7); (*(M2[39]))[35] = M1(3,8); (*(M2[39]))[38] = M1(3,9); (*(M2[39]))[44] = M1(3,11); (*(M2[39]))[45] = M1(3,12); (*(M2[39]))[48] = M1(3,13); (*(M2[39]))[49] = M1(3,14); (*(M2[39]))[52] = M1(3,15); (*(M2[39]))[57] = M1(3,16); (*(M2[39]))[58] = M1(3,17); (*(M2[39]))[61] = M1(3,18); (*(M2[39]))[66] = M1(3,19); (*(M2[39]))[91] = M1(3,20); (*(M2[39]))[92] = M1(3,21); (*(M2[39]))[96] = M1(3,22); (*(M2[39]))[106] = M1(3,23); (*(M2[40]))[30] = M1(5,5); (*(M2[40]))[34] = M1(5,7); (*(M2[40]))[35] = M1(5,8); (*(M2[40]))[38] = M1(5,9); (*(M2[40]))[44] = M1(5,11); (*(M2[40]))[45] = M1(5,12); (*(M2[40]))[48] = M1(5,13); (*(M2[40]))[49] = M1(5,14); (*(M2[40]))[52] = M1(5,15); (*(M2[40]))[57] = M1(5,16); (*(M2[40]))[58] = M1(5,17); (*(M2[40]))[61] = M1(5,18); (*(M2[40]))[66] = M1(5,19); (*(M2[40]))[91] = M1(5,20); (*(M2[40]))[92] = M1(5,21); (*(M2[40]))[96] = M1(5,22); (*(M2[40]))[106] = M1(5,23); (*(M2[41]))[31] = M1(6,6); (*(M2[41]))[34] = M1(6,7); (*(M2[41]))[35] = M1(6,8); (*(M2[41]))[38] = M1(6,9); (*(M2[41]))[44] = M1(6,11); (*(M2[41]))[45] = M1(6,12); (*(M2[41]))[48] = M1(6,13); (*(M2[41]))[49] = M1(6,14); (*(M2[41]))[52] = M1(6,15); (*(M2[41]))[57] = M1(6,16); (*(M2[41]))[58] = M1(6,17); (*(M2[41]))[61] = M1(6,18); (*(M2[41]))[66] = M1(6,19); (*(M2[41]))[91] = M1(6,20); (*(M2[41]))[92] = M1(6,21); (*(M2[41]))[96] = M1(6,22); (*(M2[41]))[106] = M1(6,23); (*(M2[42]))[43] = M1(7,10); (*(M2[42]))[45] = M1(7,12); (*(M2[42]))[52] = M1(7,15); (*(M2[42]))[66] = M1(7,19); (*(M2[42]))[106] = M1(7,23); (*(M2[43]))[6] = M1(2,2); (*(M2[43]))[15] = M1(2,7); (*(M2[43]))[16] = M1(2,8); (*(M2[43]))[19] = M1(2,9); (*(M2[43]))[30] = M1(2,11); (*(M2[43]))[31] = M1(2,12); (*(M2[43]))[34] = M1(2,13); (*(M2[43]))[35] = M1(2,14); (*(M2[43]))[38] = M1(2,15); (*(M2[43]))[48] = M1(2,16); (*(M2[43]))[49] = M1(2,17); (*(M2[43]))[52] = M1(2,18); (*(M2[43]))[61] = M1(2,19); (*(M2[43]))[76] = M1(2,20); (*(M2[43]))[77] = M1(2,21); (*(M2[43]))[81] = M1(2,22); (*(M2[43]))[96] = M1(2,23); (*(M2[44]))[7] = M1(3,3); (*(M2[44]))[15] = M1(3,7); (*(M2[44]))[16] = M1(3,8); (*(M2[44]))[19] = M1(3,9); (*(M2[44]))[30] = M1(3,11); (*(M2[44]))[31] = M1(3,12); (*(M2[44]))[34] = M1(3,13); (*(M2[44]))[35] = M1(3,14); (*(M2[44]))[38] = M1(3,15); (*(M2[44]))[48] = M1(3,16); (*(M2[44]))[49] = M1(3,17); (*(M2[44]))[52] = M1(3,18); (*(M2[44]))[61] = M1(3,19); (*(M2[44]))[76] = M1(3,20); (*(M2[44]))[77] = M1(3,21); (*(M2[44]))[81] = M1(3,22); (*(M2[44]))[96] = M1(3,23); (*(M2[45]))[10] = M1(4,4); (*(M2[45]))[15] = M1(4,7); (*(M2[45]))[16] = M1(4,8); (*(M2[45]))[19] = M1(4,9); (*(M2[45]))[30] = M1(4,11); (*(M2[45]))[31] = M1(4,12); (*(M2[45]))[34] = M1(4,13); (*(M2[45]))[35] = M1(4,14); (*(M2[45]))[38] = M1(4,15); (*(M2[45]))[48] = M1(4,16); (*(M2[45]))[49] = M1(4,17); (*(M2[45]))[52] = M1(4,18); (*(M2[45]))[61] = M1(4,19); (*(M2[45]))[76] = M1(4,20); (*(M2[45]))[77] = M1(4,21); (*(M2[45]))[81] = M1(4,22); (*(M2[45]))[96] = M1(4,23); (*(M2[46]))[11] = M1(5,5); (*(M2[46]))[15] = M1(5,7); (*(M2[46]))[16] = M1(5,8); (*(M2[46]))[19] = M1(5,9); (*(M2[46]))[30] = M1(5,11); (*(M2[46]))[31] = M1(5,12); (*(M2[46]))[34] = M1(5,13); (*(M2[46]))[35] = M1(5,14); (*(M2[46]))[38] = M1(5,15); (*(M2[46]))[48] = M1(5,16); (*(M2[46]))[49] = M1(5,17); (*(M2[46]))[52] = M1(5,18); (*(M2[46]))[61] = M1(5,19); (*(M2[46]))[76] = M1(5,20); (*(M2[46]))[77] = M1(5,21); (*(M2[46]))[81] = M1(5,22); (*(M2[46]))[96] = M1(5,23); (*(M2[47]))[12] = M1(6,6); (*(M2[47]))[15] = M1(6,7); (*(M2[47]))[16] = M1(6,8); (*(M2[47]))[19] = M1(6,9); (*(M2[47]))[30] = M1(6,11); (*(M2[47]))[31] = M1(6,12); (*(M2[47]))[34] = M1(6,13); (*(M2[47]))[35] = M1(6,14); (*(M2[47]))[38] = M1(6,15); (*(M2[47]))[48] = M1(6,16); (*(M2[47]))[49] = M1(6,17); (*(M2[47]))[52] = M1(6,18); (*(M2[47]))[61] = M1(6,19); (*(M2[47]))[76] = M1(6,20); (*(M2[47]))[77] = M1(6,21); (*(M2[47]))[81] = M1(6,22); (*(M2[47]))[96] = M1(6,23); (*(M2[48]))[29] = M1(7,10); (*(M2[48]))[31] = M1(7,12); (*(M2[48]))[38] = M1(7,15); (*(M2[48]))[61] = M1(7,19); (*(M2[48]))[96] = M1(7,23); (*(M2[49]))[1] = M1(1,1); (*(M2[49]))[11] = M1(1,7); (*(M2[49]))[12] = M1(1,8); (*(M2[49]))[16] = M1(1,9); (*(M2[49]))[25] = M1(1,11); (*(M2[49]))[26] = M1(1,12); (*(M2[49]))[30] = M1(1,13); (*(M2[49]))[31] = M1(1,14); (*(M2[49]))[35] = M1(1,15); (*(M2[49]))[44] = M1(1,16); (*(M2[49]))[45] = M1(1,17); (*(M2[49]))[49] = M1(1,18); (*(M2[49]))[58] = M1(1,19); (*(M2[49]))[72] = M1(1,20); (*(M2[49]))[73] = M1(1,21); (*(M2[49]))[77] = M1(1,22); (*(M2[49]))[92] = M1(1,23); (*(M2[50]))[2] = M1(2,2); (*(M2[50]))[11] = M1(2,7); (*(M2[50]))[12] = M1(2,8); (*(M2[50]))[16] = M1(2,9); (*(M2[50]))[25] = M1(2,11); (*(M2[50]))[26] = M1(2,12); (*(M2[50]))[30] = M1(2,13); (*(M2[50]))[31] = M1(2,14); (*(M2[50]))[35] = M1(2,15); (*(M2[50]))[44] = M1(2,16); (*(M2[50]))[45] = M1(2,17); (*(M2[50]))[49] = M1(2,18); (*(M2[50]))[58] = M1(2,19); (*(M2[50]))[72] = M1(2,20); (*(M2[50]))[73] = M1(2,21); (*(M2[50]))[77] = M1(2,22); (*(M2[50]))[92] = M1(2,23); (*(M2[51]))[3] = M1(3,3); (*(M2[51]))[11] = M1(3,7); (*(M2[51]))[12] = M1(3,8); (*(M2[51]))[16] = M1(3,9); (*(M2[51]))[25] = M1(3,11); (*(M2[51]))[26] = M1(3,12); (*(M2[51]))[30] = M1(3,13); (*(M2[51]))[31] = M1(3,14); (*(M2[51]))[35] = M1(3,15); (*(M2[51]))[44] = M1(3,16); (*(M2[51]))[45] = M1(3,17); (*(M2[51]))[49] = M1(3,18); (*(M2[51]))[58] = M1(3,19); (*(M2[51]))[72] = M1(3,20); (*(M2[51]))[73] = M1(3,21); (*(M2[51]))[77] = M1(3,22); (*(M2[51]))[92] = M1(3,23); (*(M2[52]))[5] = M1(4,4); (*(M2[52]))[11] = M1(4,7); (*(M2[52]))[12] = M1(4,8); (*(M2[52]))[16] = M1(4,9); (*(M2[52]))[25] = M1(4,11); (*(M2[52]))[26] = M1(4,12); (*(M2[52]))[30] = M1(4,13); (*(M2[52]))[31] = M1(4,14); (*(M2[52]))[35] = M1(4,15); (*(M2[52]))[44] = M1(4,16); (*(M2[52]))[45] = M1(4,17); (*(M2[52]))[49] = M1(4,18); (*(M2[52]))[58] = M1(4,19); (*(M2[52]))[72] = M1(4,20); (*(M2[52]))[73] = M1(4,21); (*(M2[52]))[77] = M1(4,22); (*(M2[52]))[92] = M1(4,23); (*(M2[53]))[6] = M1(5,5); (*(M2[53]))[11] = M1(5,7); (*(M2[53]))[12] = M1(5,8); (*(M2[53]))[16] = M1(5,9); (*(M2[53]))[25] = M1(5,11); (*(M2[53]))[26] = M1(5,12); (*(M2[53]))[30] = M1(5,13); (*(M2[53]))[31] = M1(5,14); (*(M2[53]))[35] = M1(5,15); (*(M2[53]))[44] = M1(5,16); (*(M2[53]))[45] = M1(5,17); (*(M2[53]))[49] = M1(5,18); (*(M2[53]))[58] = M1(5,19); (*(M2[53]))[72] = M1(5,20); (*(M2[53]))[73] = M1(5,21); (*(M2[53]))[77] = M1(5,22); (*(M2[53]))[92] = M1(5,23); (*(M2[54]))[7] = M1(6,6); (*(M2[54]))[11] = M1(6,7); (*(M2[54]))[12] = M1(6,8); (*(M2[54]))[16] = M1(6,9); (*(M2[54]))[25] = M1(6,11); (*(M2[54]))[26] = M1(6,12); (*(M2[54]))[30] = M1(6,13); (*(M2[54]))[31] = M1(6,14); (*(M2[54]))[35] = M1(6,15); (*(M2[54]))[44] = M1(6,16); (*(M2[54]))[45] = M1(6,17); (*(M2[54]))[49] = M1(6,18); (*(M2[54]))[58] = M1(6,19); (*(M2[54]))[72] = M1(6,20); (*(M2[54]))[73] = M1(6,21); (*(M2[54]))[77] = M1(6,22); (*(M2[54]))[92] = M1(6,23); (*(M2[55]))[24] = M1(7,10); (*(M2[55]))[26] = M1(7,12); (*(M2[55]))[35] = M1(7,15); (*(M2[55]))[58] = M1(7,19); (*(M2[55]))[92] = M1(7,23); (*(M2[56]))[24] = M1(2,2); (*(M2[56]))[33] = M1(2,7); (*(M2[56]))[34] = M1(2,8); (*(M2[56]))[37] = M1(2,9); (*(M2[56]))[43] = M1(2,11); (*(M2[56]))[44] = M1(2,12); (*(M2[56]))[47] = M1(2,13); (*(M2[56]))[48] = M1(2,14); (*(M2[56]))[51] = M1(2,15); (*(M2[56]))[56] = M1(2,16); (*(M2[56]))[57] = M1(2,17); (*(M2[56]))[60] = M1(2,18); (*(M2[56]))[65] = M1(2,19); (*(M2[56]))[90] = M1(2,20); (*(M2[56]))[91] = M1(2,21); (*(M2[56]))[95] = M1(2,22); (*(M2[56]))[105] = M1(2,23); (*(M2[57]))[25] = M1(3,3); (*(M2[57]))[33] = M1(3,7); (*(M2[57]))[34] = M1(3,8); (*(M2[57]))[37] = M1(3,9); (*(M2[57]))[43] = M1(3,11); (*(M2[57]))[44] = M1(3,12); (*(M2[57]))[47] = M1(3,13); (*(M2[57]))[48] = M1(3,14); (*(M2[57]))[51] = M1(3,15); (*(M2[57]))[56] = M1(3,16); (*(M2[57]))[57] = M1(3,17); (*(M2[57]))[60] = M1(3,18); (*(M2[57]))[65] = M1(3,19); (*(M2[57]))[90] = M1(3,20); (*(M2[57]))[91] = M1(3,21); (*(M2[57]))[95] = M1(3,22); (*(M2[57]))[105] = M1(3,23); (*(M2[58]))[29] = M1(5,5); (*(M2[58]))[33] = M1(5,7); (*(M2[58]))[34] = M1(5,8); (*(M2[58]))[37] = M1(5,9); (*(M2[58]))[43] = M1(5,11); (*(M2[58]))[44] = M1(5,12); (*(M2[58]))[47] = M1(5,13); (*(M2[58]))[48] = M1(5,14); (*(M2[58]))[51] = M1(5,15); (*(M2[58]))[56] = M1(5,16); (*(M2[58]))[57] = M1(5,17); (*(M2[58]))[60] = M1(5,18); (*(M2[58]))[65] = M1(5,19); (*(M2[58]))[90] = M1(5,20); (*(M2[58]))[91] = M1(5,21); (*(M2[58]))[95] = M1(5,22); (*(M2[58]))[105] = M1(5,23); (*(M2[59]))[30] = M1(6,6); (*(M2[59]))[33] = M1(6,7); (*(M2[59]))[34] = M1(6,8); (*(M2[59]))[37] = M1(6,9); (*(M2[59]))[43] = M1(6,11); (*(M2[59]))[44] = M1(6,12); (*(M2[59]))[47] = M1(6,13); (*(M2[59]))[48] = M1(6,14); (*(M2[59]))[51] = M1(6,15); (*(M2[59]))[56] = M1(6,16); (*(M2[59]))[57] = M1(6,17); (*(M2[59]))[60] = M1(6,18); (*(M2[59]))[65] = M1(6,19); (*(M2[59]))[90] = M1(6,20); (*(M2[59]))[91] = M1(6,21); (*(M2[59]))[95] = M1(6,22); (*(M2[59]))[105] = M1(6,23); (*(M2[60]))[42] = M1(7,10); (*(M2[60]))[44] = M1(7,12); (*(M2[60]))[51] = M1(7,15); (*(M2[60]))[65] = M1(7,19); (*(M2[60]))[105] = M1(7,23); (*(M2[61]))[5] = M1(2,2); (*(M2[61]))[14] = M1(2,7); (*(M2[61]))[15] = M1(2,8); (*(M2[61]))[18] = M1(2,9); (*(M2[61]))[29] = M1(2,11); (*(M2[61]))[30] = M1(2,12); (*(M2[61]))[33] = M1(2,13); (*(M2[61]))[34] = M1(2,14); (*(M2[61]))[37] = M1(2,15); (*(M2[61]))[47] = M1(2,16); (*(M2[61]))[48] = M1(2,17); (*(M2[61]))[51] = M1(2,18); (*(M2[61]))[60] = M1(2,19); (*(M2[61]))[75] = M1(2,20); (*(M2[61]))[76] = M1(2,21); (*(M2[61]))[80] = M1(2,22); (*(M2[61]))[95] = M1(2,23); (*(M2[62]))[6] = M1(3,3); (*(M2[62]))[14] = M1(3,7); (*(M2[62]))[15] = M1(3,8); (*(M2[62]))[18] = M1(3,9); (*(M2[62]))[29] = M1(3,11); (*(M2[62]))[30] = M1(3,12); (*(M2[62]))[33] = M1(3,13); (*(M2[62]))[34] = M1(3,14); (*(M2[62]))[37] = M1(3,15); (*(M2[62]))[47] = M1(3,16); (*(M2[62]))[48] = M1(3,17); (*(M2[62]))[51] = M1(3,18); (*(M2[62]))[60] = M1(3,19); (*(M2[62]))[75] = M1(3,20); (*(M2[62]))[76] = M1(3,21); (*(M2[62]))[80] = M1(3,22); (*(M2[62]))[95] = M1(3,23); (*(M2[63]))[9] = M1(4,4); (*(M2[63]))[14] = M1(4,7); (*(M2[63]))[15] = M1(4,8); (*(M2[63]))[18] = M1(4,9); (*(M2[63]))[29] = M1(4,11); (*(M2[63]))[30] = M1(4,12); (*(M2[63]))[33] = M1(4,13); (*(M2[63]))[34] = M1(4,14); (*(M2[63]))[37] = M1(4,15); (*(M2[63]))[47] = M1(4,16); (*(M2[63]))[48] = M1(4,17); (*(M2[63]))[51] = M1(4,18); (*(M2[63]))[60] = M1(4,19); (*(M2[63]))[75] = M1(4,20); (*(M2[63]))[76] = M1(4,21); (*(M2[63]))[80] = M1(4,22); (*(M2[63]))[95] = M1(4,23); (*(M2[64]))[10] = M1(5,5); (*(M2[64]))[14] = M1(5,7); (*(M2[64]))[15] = M1(5,8); (*(M2[64]))[18] = M1(5,9); (*(M2[64]))[29] = M1(5,11); (*(M2[64]))[30] = M1(5,12); (*(M2[64]))[33] = M1(5,13); (*(M2[64]))[34] = M1(5,14); (*(M2[64]))[37] = M1(5,15); (*(M2[64]))[47] = M1(5,16); (*(M2[64]))[48] = M1(5,17); (*(M2[64]))[51] = M1(5,18); (*(M2[64]))[60] = M1(5,19); (*(M2[64]))[75] = M1(5,20); (*(M2[64]))[76] = M1(5,21); (*(M2[64]))[80] = M1(5,22); (*(M2[64]))[95] = M1(5,23); (*(M2[65]))[11] = M1(6,6); (*(M2[65]))[14] = M1(6,7); (*(M2[65]))[15] = M1(6,8); (*(M2[65]))[18] = M1(6,9); (*(M2[65]))[29] = M1(6,11); (*(M2[65]))[30] = M1(6,12); (*(M2[65]))[33] = M1(6,13); (*(M2[65]))[34] = M1(6,14); (*(M2[65]))[37] = M1(6,15); (*(M2[65]))[47] = M1(6,16); (*(M2[65]))[48] = M1(6,17); (*(M2[65]))[51] = M1(6,18); (*(M2[65]))[60] = M1(6,19); (*(M2[65]))[75] = M1(6,20); (*(M2[65]))[76] = M1(6,21); (*(M2[65]))[80] = M1(6,22); (*(M2[65]))[95] = M1(6,23); (*(M2[66]))[28] = M1(7,10); (*(M2[66]))[30] = M1(7,12); (*(M2[66]))[37] = M1(7,15); (*(M2[66]))[60] = M1(7,19); (*(M2[66]))[95] = M1(7,23); (*(M2[67]))[0] = M1(1,1); (*(M2[67]))[10] = M1(1,7); (*(M2[67]))[11] = M1(1,8); (*(M2[67]))[15] = M1(1,9); (*(M2[67]))[24] = M1(1,11); (*(M2[67]))[25] = M1(1,12); (*(M2[67]))[29] = M1(1,13); (*(M2[67]))[30] = M1(1,14); (*(M2[67]))[34] = M1(1,15); (*(M2[67]))[43] = M1(1,16); (*(M2[67]))[44] = M1(1,17); (*(M2[67]))[48] = M1(1,18); (*(M2[67]))[57] = M1(1,19); (*(M2[67]))[71] = M1(1,20); (*(M2[67]))[72] = M1(1,21); (*(M2[67]))[76] = M1(1,22); (*(M2[67]))[91] = M1(1,23); (*(M2[68]))[1] = M1(2,2); (*(M2[68]))[10] = M1(2,7); (*(M2[68]))[11] = M1(2,8); (*(M2[68]))[15] = M1(2,9); (*(M2[68]))[24] = M1(2,11); (*(M2[68]))[25] = M1(2,12); (*(M2[68]))[29] = M1(2,13); (*(M2[68]))[30] = M1(2,14); (*(M2[68]))[34] = M1(2,15); (*(M2[68]))[43] = M1(2,16); (*(M2[68]))[44] = M1(2,17); (*(M2[68]))[48] = M1(2,18); (*(M2[68]))[57] = M1(2,19); (*(M2[68]))[71] = M1(2,20); (*(M2[68]))[72] = M1(2,21); (*(M2[68]))[76] = M1(2,22); (*(M2[68]))[91] = M1(2,23); (*(M2[69]))[2] = M1(3,3); (*(M2[69]))[10] = M1(3,7); (*(M2[69]))[11] = M1(3,8); (*(M2[69]))[15] = M1(3,9); (*(M2[69]))[24] = M1(3,11); (*(M2[69]))[25] = M1(3,12); (*(M2[69]))[29] = M1(3,13); (*(M2[69]))[30] = M1(3,14); (*(M2[69]))[34] = M1(3,15); (*(M2[69]))[43] = M1(3,16); (*(M2[69]))[44] = M1(3,17); (*(M2[69]))[48] = M1(3,18); (*(M2[69]))[57] = M1(3,19); (*(M2[69]))[71] = M1(3,20); (*(M2[69]))[72] = M1(3,21); (*(M2[69]))[76] = M1(3,22); (*(M2[69]))[91] = M1(3,23); (*(M2[70]))[4] = M1(4,4); (*(M2[70]))[10] = M1(4,7); (*(M2[70]))[11] = M1(4,8); (*(M2[70]))[15] = M1(4,9); (*(M2[70]))[24] = M1(4,11); (*(M2[70]))[25] = M1(4,12); (*(M2[70]))[29] = M1(4,13); (*(M2[70]))[30] = M1(4,14); (*(M2[70]))[34] = M1(4,15); (*(M2[70]))[43] = M1(4,16); (*(M2[70]))[44] = M1(4,17); (*(M2[70]))[48] = M1(4,18); (*(M2[70]))[57] = M1(4,19); (*(M2[70]))[71] = M1(4,20); (*(M2[70]))[72] = M1(4,21); (*(M2[70]))[76] = M1(4,22); (*(M2[70]))[91] = M1(4,23); (*(M2[71]))[5] = M1(5,5); (*(M2[71]))[10] = M1(5,7); (*(M2[71]))[11] = M1(5,8); (*(M2[71]))[15] = M1(5,9); (*(M2[71]))[24] = M1(5,11); (*(M2[71]))[25] = M1(5,12); (*(M2[71]))[29] = M1(5,13); (*(M2[71]))[30] = M1(5,14); (*(M2[71]))[34] = M1(5,15); (*(M2[71]))[43] = M1(5,16); (*(M2[71]))[44] = M1(5,17); (*(M2[71]))[48] = M1(5,18); (*(M2[71]))[57] = M1(5,19); (*(M2[71]))[71] = M1(5,20); (*(M2[71]))[72] = M1(5,21); (*(M2[71]))[76] = M1(5,22); (*(M2[71]))[91] = M1(5,23); (*(M2[72]))[6] = M1(6,6); (*(M2[72]))[10] = M1(6,7); (*(M2[72]))[11] = M1(6,8); (*(M2[72]))[15] = M1(6,9); (*(M2[72]))[24] = M1(6,11); (*(M2[72]))[25] = M1(6,12); (*(M2[72]))[29] = M1(6,13); (*(M2[72]))[30] = M1(6,14); (*(M2[72]))[34] = M1(6,15); (*(M2[72]))[43] = M1(6,16); (*(M2[72]))[44] = M1(6,17); (*(M2[72]))[48] = M1(6,18); (*(M2[72]))[57] = M1(6,19); (*(M2[72]))[71] = M1(6,20); (*(M2[72]))[72] = M1(6,21); (*(M2[72]))[76] = M1(6,22); (*(M2[72]))[91] = M1(6,23); (*(M2[73]))[23] = M1(7,10); (*(M2[73]))[25] = M1(7,12); (*(M2[73]))[34] = M1(7,15); (*(M2[73]))[57] = M1(7,19); (*(M2[73]))[91] = M1(7,23); (*(M2[74]))[0] = M1(2,2); (*(M2[74]))[9] = M1(2,7); (*(M2[74]))[10] = M1(2,8); (*(M2[74]))[14] = M1(2,9); (*(M2[74]))[23] = M1(2,11); (*(M2[74]))[24] = M1(2,12); (*(M2[74]))[28] = M1(2,13); (*(M2[74]))[29] = M1(2,14); (*(M2[74]))[33] = M1(2,15); (*(M2[74]))[42] = M1(2,16); (*(M2[74]))[43] = M1(2,17); (*(M2[74]))[47] = M1(2,18); (*(M2[74]))[56] = M1(2,19); (*(M2[74]))[70] = M1(2,20); (*(M2[74]))[71] = M1(2,21); (*(M2[74]))[75] = M1(2,22); (*(M2[74]))[90] = M1(2,23); (*(M2[75]))[1] = M1(3,3); (*(M2[75]))[9] = M1(3,7); (*(M2[75]))[10] = M1(3,8); (*(M2[75]))[14] = M1(3,9); (*(M2[75]))[23] = M1(3,11); (*(M2[75]))[24] = M1(3,12); (*(M2[75]))[28] = M1(3,13); (*(M2[75]))[29] = M1(3,14); (*(M2[75]))[33] = M1(3,15); (*(M2[75]))[42] = M1(3,16); (*(M2[75]))[43] = M1(3,17); (*(M2[75]))[47] = M1(3,18); (*(M2[75]))[56] = M1(3,19); (*(M2[75]))[70] = M1(3,20); (*(M2[75]))[71] = M1(3,21); (*(M2[75]))[75] = M1(3,22); (*(M2[75]))[90] = M1(3,23); (*(M2[76]))[4] = M1(5,5); (*(M2[76]))[9] = M1(5,7); (*(M2[76]))[10] = M1(5,8); (*(M2[76]))[14] = M1(5,9); (*(M2[76]))[23] = M1(5,11); (*(M2[76]))[24] = M1(5,12); (*(M2[76]))[28] = M1(5,13); (*(M2[76]))[29] = M1(5,14); (*(M2[76]))[33] = M1(5,15); (*(M2[76]))[42] = M1(5,16); (*(M2[76]))[43] = M1(5,17); (*(M2[76]))[47] = M1(5,18); (*(M2[76]))[56] = M1(5,19); (*(M2[76]))[70] = M1(5,20); (*(M2[76]))[71] = M1(5,21); (*(M2[76]))[75] = M1(5,22); (*(M2[76]))[90] = M1(5,23); (*(M2[77]))[5] = M1(6,6); (*(M2[77]))[9] = M1(6,7); (*(M2[77]))[10] = M1(6,8); (*(M2[77]))[14] = M1(6,9); (*(M2[77]))[23] = M1(6,11); (*(M2[77]))[24] = M1(6,12); (*(M2[77]))[28] = M1(6,13); (*(M2[77]))[29] = M1(6,14); (*(M2[77]))[33] = M1(6,15); (*(M2[77]))[42] = M1(6,16); (*(M2[77]))[43] = M1(6,17); (*(M2[77]))[47] = M1(6,18); (*(M2[77]))[56] = M1(6,19); (*(M2[77]))[70] = M1(6,20); (*(M2[77]))[71] = M1(6,21); (*(M2[77]))[75] = M1(6,22); (*(M2[77]))[90] = M1(6,23); (*(M2[78]))[115] = M1(7,10); (*(M2[78]))[117] = M1(7,12); (*(M2[78]))[120] = M1(7,15); (*(M2[78]))[124] = M1(7,19); (*(M2[78]))[144] = M1(7,23); (*(M2[79]))[97] = M1(2,2); (*(M2[79]))[102] = M1(2,7); (*(M2[79]))[103] = M1(2,8); (*(M2[79]))[104] = M1(2,9); (*(M2[79]))[110] = M1(2,11); (*(M2[79]))[111] = M1(2,12); (*(M2[79]))[112] = M1(2,13); (*(M2[79]))[113] = M1(2,14); (*(M2[79]))[114] = M1(2,15); (*(M2[79]))[118] = M1(2,16); (*(M2[79]))[119] = M1(2,17); (*(M2[79]))[120] = M1(2,18); (*(M2[79]))[123] = M1(2,19); (*(M2[79]))[138] = M1(2,20); (*(M2[79]))[139] = M1(2,21); (*(M2[79]))[140] = M1(2,22); (*(M2[79]))[143] = M1(2,23); (*(M2[80]))[98] = M1(3,3); (*(M2[80]))[102] = M1(3,7); (*(M2[80]))[103] = M1(3,8); (*(M2[80]))[104] = M1(3,9); (*(M2[80]))[110] = M1(3,11); (*(M2[80]))[111] = M1(3,12); (*(M2[80]))[112] = M1(3,13); (*(M2[80]))[113] = M1(3,14); (*(M2[80]))[114] = M1(3,15); (*(M2[80]))[118] = M1(3,16); (*(M2[80]))[119] = M1(3,17); (*(M2[80]))[120] = M1(3,18); (*(M2[80]))[123] = M1(3,19); (*(M2[80]))[138] = M1(3,20); (*(M2[80]))[139] = M1(3,21); (*(M2[80]))[140] = M1(3,22); (*(M2[80]))[143] = M1(3,23); (*(M2[81]))[100] = M1(5,5); (*(M2[81]))[102] = M1(5,7); (*(M2[81]))[103] = M1(5,8); (*(M2[81]))[104] = M1(5,9); (*(M2[81]))[110] = M1(5,11); (*(M2[81]))[111] = M1(5,12); (*(M2[81]))[112] = M1(5,13); (*(M2[81]))[113] = M1(5,14); (*(M2[81]))[114] = M1(5,15); (*(M2[81]))[118] = M1(5,16); (*(M2[81]))[119] = M1(5,17); (*(M2[81]))[120] = M1(5,18); (*(M2[81]))[123] = M1(5,19); (*(M2[81]))[138] = M1(5,20); (*(M2[81]))[139] = M1(5,21); (*(M2[81]))[140] = M1(5,22); (*(M2[81]))[143] = M1(5,23); (*(M2[82]))[101] = M1(6,6); (*(M2[82]))[102] = M1(6,7); (*(M2[82]))[103] = M1(6,8); (*(M2[82]))[104] = M1(6,9); (*(M2[82]))[110] = M1(6,11); (*(M2[82]))[111] = M1(6,12); (*(M2[82]))[112] = M1(6,13); (*(M2[82]))[113] = M1(6,14); (*(M2[82]))[114] = M1(6,15); (*(M2[82]))[118] = M1(6,16); (*(M2[82]))[119] = M1(6,17); (*(M2[82]))[120] = M1(6,18); (*(M2[82]))[123] = M1(6,19); (*(M2[82]))[138] = M1(6,20); (*(M2[82]))[139] = M1(6,21); (*(M2[82]))[140] = M1(6,22); (*(M2[82]))[143] = M1(6,23); (*(M2[83]))[109] = M1(7,10); (*(M2[83]))[111] = M1(7,12); (*(M2[83]))[114] = M1(7,15); (*(M2[83]))[123] = M1(7,19); (*(M2[83]))[143] = M1(7,23); (*(M2[84]))[82] = M1(2,2); (*(M2[84]))[87] = M1(2,7); (*(M2[84]))[88] = M1(2,8); (*(M2[84]))[89] = M1(2,9); (*(M2[84]))[100] = M1(2,11); (*(M2[84]))[101] = M1(2,12); (*(M2[84]))[102] = M1(2,13); (*(M2[84]))[103] = M1(2,14); (*(M2[84]))[104] = M1(2,15); (*(M2[84]))[112] = M1(2,16); (*(M2[84]))[113] = M1(2,17); (*(M2[84]))[114] = M1(2,18); (*(M2[84]))[120] = M1(2,19); (*(M2[84]))[132] = M1(2,20); (*(M2[84]))[133] = M1(2,21); (*(M2[84]))[134] = M1(2,22); (*(M2[84]))[140] = M1(2,23); (*(M2[85]))[83] = M1(3,3); (*(M2[85]))[87] = M1(3,7); (*(M2[85]))[88] = M1(3,8); (*(M2[85]))[89] = M1(3,9); (*(M2[85]))[100] = M1(3,11); (*(M2[85]))[101] = M1(3,12); (*(M2[85]))[102] = M1(3,13); (*(M2[85]))[103] = M1(3,14); (*(M2[85]))[104] = M1(3,15); (*(M2[85]))[112] = M1(3,16); (*(M2[85]))[113] = M1(3,17); (*(M2[85]))[114] = M1(3,18); (*(M2[85]))[120] = M1(3,19); (*(M2[85]))[132] = M1(3,20); (*(M2[85]))[133] = M1(3,21); (*(M2[85]))[134] = M1(3,22); (*(M2[85]))[140] = M1(3,23); (*(M2[86]))[84] = M1(4,4); (*(M2[86]))[87] = M1(4,7); (*(M2[86]))[88] = M1(4,8); (*(M2[86]))[89] = M1(4,9); (*(M2[86]))[100] = M1(4,11); (*(M2[86]))[101] = M1(4,12); (*(M2[86]))[102] = M1(4,13); (*(M2[86]))[103] = M1(4,14); (*(M2[86]))[104] = M1(4,15); (*(M2[86]))[112] = M1(4,16); (*(M2[86]))[113] = M1(4,17); (*(M2[86]))[114] = M1(4,18); (*(M2[86]))[120] = M1(4,19); (*(M2[86]))[132] = M1(4,20); (*(M2[86]))[133] = M1(4,21); (*(M2[86]))[134] = M1(4,22); (*(M2[86]))[140] = M1(4,23); (*(M2[87]))[85] = M1(5,5); (*(M2[87]))[87] = M1(5,7); (*(M2[87]))[88] = M1(5,8); (*(M2[87]))[89] = M1(5,9); (*(M2[87]))[100] = M1(5,11); (*(M2[87]))[101] = M1(5,12); (*(M2[87]))[102] = M1(5,13); (*(M2[87]))[103] = M1(5,14); (*(M2[87]))[104] = M1(5,15); (*(M2[87]))[112] = M1(5,16); (*(M2[87]))[113] = M1(5,17); (*(M2[87]))[114] = M1(5,18); (*(M2[87]))[120] = M1(5,19); (*(M2[87]))[132] = M1(5,20); (*(M2[87]))[133] = M1(5,21); (*(M2[87]))[134] = M1(5,22); (*(M2[87]))[140] = M1(5,23); (*(M2[88]))[86] = M1(6,6); (*(M2[88]))[87] = M1(6,7); (*(M2[88]))[88] = M1(6,8); (*(M2[88]))[89] = M1(6,9); (*(M2[88]))[100] = M1(6,11); (*(M2[88]))[101] = M1(6,12); (*(M2[88]))[102] = M1(6,13); (*(M2[88]))[103] = M1(6,14); (*(M2[88]))[104] = M1(6,15); (*(M2[88]))[112] = M1(6,16); (*(M2[88]))[113] = M1(6,17); (*(M2[88]))[114] = M1(6,18); (*(M2[88]))[120] = M1(6,19); (*(M2[88]))[132] = M1(6,20); (*(M2[88]))[133] = M1(6,21); (*(M2[88]))[134] = M1(6,22); (*(M2[88]))[140] = M1(6,23); (*(M2[89]))[99] = M1(7,10); (*(M2[89]))[101] = M1(7,12); (*(M2[89]))[104] = M1(7,15); (*(M2[89]))[120] = M1(7,19); (*(M2[89]))[140] = M1(7,23); (*(M2[90]))[93] = M1(2,2); (*(M2[90]))[100] = M1(2,7); (*(M2[90]))[101] = M1(2,8); (*(M2[90]))[103] = M1(2,9); (*(M2[90]))[107] = M1(2,11); (*(M2[90]))[108] = M1(2,12); (*(M2[90]))[110] = M1(2,13); (*(M2[90]))[111] = M1(2,14); (*(M2[90]))[113] = M1(2,15); (*(M2[90]))[116] = M1(2,16); (*(M2[90]))[117] = M1(2,17); (*(M2[90]))[119] = M1(2,18); (*(M2[90]))[122] = M1(2,19); (*(M2[90]))[136] = M1(2,20); (*(M2[90]))[137] = M1(2,21); (*(M2[90]))[139] = M1(2,22); (*(M2[90]))[142] = M1(2,23); (*(M2[91]))[94] = M1(3,3); (*(M2[91]))[100] = M1(3,7); (*(M2[91]))[101] = M1(3,8); (*(M2[91]))[103] = M1(3,9); (*(M2[91]))[107] = M1(3,11); (*(M2[91]))[108] = M1(3,12); (*(M2[91]))[110] = M1(3,13); (*(M2[91]))[111] = M1(3,14); (*(M2[91]))[113] = M1(3,15); (*(M2[91]))[116] = M1(3,16); (*(M2[91]))[117] = M1(3,17); (*(M2[91]))[119] = M1(3,18); (*(M2[91]))[122] = M1(3,19); (*(M2[91]))[136] = M1(3,20); (*(M2[91]))[137] = M1(3,21); (*(M2[91]))[139] = M1(3,22); (*(M2[91]))[142] = M1(3,23); (*(M2[92]))[97] = M1(5,5); (*(M2[92]))[100] = M1(5,7); (*(M2[92]))[101] = M1(5,8); (*(M2[92]))[103] = M1(5,9); (*(M2[92]))[107] = M1(5,11); (*(M2[92]))[108] = M1(5,12); (*(M2[92]))[110] = M1(5,13); (*(M2[92]))[111] = M1(5,14); (*(M2[92]))[113] = M1(5,15); (*(M2[92]))[116] = M1(5,16); (*(M2[92]))[117] = M1(5,17); (*(M2[92]))[119] = M1(5,18); (*(M2[92]))[122] = M1(5,19); (*(M2[92]))[136] = M1(5,20); (*(M2[92]))[137] = M1(5,21); (*(M2[92]))[139] = M1(5,22); (*(M2[92]))[142] = M1(5,23); (*(M2[93]))[98] = M1(6,6); (*(M2[93]))[100] = M1(6,7); (*(M2[93]))[101] = M1(6,8); (*(M2[93]))[103] = M1(6,9); (*(M2[93]))[107] = M1(6,11); (*(M2[93]))[108] = M1(6,12); (*(M2[93]))[110] = M1(6,13); (*(M2[93]))[111] = M1(6,14); (*(M2[93]))[113] = M1(6,15); (*(M2[93]))[116] = M1(6,16); (*(M2[93]))[117] = M1(6,17); (*(M2[93]))[119] = M1(6,18); (*(M2[93]))[122] = M1(6,19); (*(M2[93]))[136] = M1(6,20); (*(M2[93]))[137] = M1(6,21); (*(M2[93]))[139] = M1(6,22); (*(M2[93]))[142] = M1(6,23); (*(M2[94]))[106] = M1(7,10); (*(M2[94]))[108] = M1(7,12); (*(M2[94]))[113] = M1(7,15); (*(M2[94]))[122] = M1(7,19); (*(M2[94]))[142] = M1(7,23); (*(M2[95]))[78] = M1(2,2); (*(M2[95]))[85] = M1(2,7); (*(M2[95]))[86] = M1(2,8); (*(M2[95]))[88] = M1(2,9); (*(M2[95]))[97] = M1(2,11); (*(M2[95]))[98] = M1(2,12); (*(M2[95]))[100] = M1(2,13); (*(M2[95]))[101] = M1(2,14); (*(M2[95]))[103] = M1(2,15); (*(M2[95]))[110] = M1(2,16); (*(M2[95]))[111] = M1(2,17); (*(M2[95]))[113] = M1(2,18); (*(M2[95]))[119] = M1(2,19); (*(M2[95]))[130] = M1(2,20); (*(M2[95]))[131] = M1(2,21); (*(M2[95]))[133] = M1(2,22); (*(M2[95]))[139] = M1(2,23); (*(M2[96]))[79] = M1(3,3); (*(M2[96]))[85] = M1(3,7); (*(M2[96]))[86] = M1(3,8); (*(M2[96]))[88] = M1(3,9); (*(M2[96]))[97] = M1(3,11); (*(M2[96]))[98] = M1(3,12); (*(M2[96]))[100] = M1(3,13); (*(M2[96]))[101] = M1(3,14); (*(M2[96]))[103] = M1(3,15); (*(M2[96]))[110] = M1(3,16); (*(M2[96]))[111] = M1(3,17); (*(M2[96]))[113] = M1(3,18); (*(M2[96]))[119] = M1(3,19); (*(M2[96]))[130] = M1(3,20); (*(M2[96]))[131] = M1(3,21); (*(M2[96]))[133] = M1(3,22); (*(M2[96]))[139] = M1(3,23); (*(M2[97]))[81] = M1(4,4); (*(M2[97]))[85] = M1(4,7); (*(M2[97]))[86] = M1(4,8); (*(M2[97]))[88] = M1(4,9); (*(M2[97]))[97] = M1(4,11); (*(M2[97]))[98] = M1(4,12); (*(M2[97]))[100] = M1(4,13); (*(M2[97]))[101] = M1(4,14); (*(M2[97]))[103] = M1(4,15); (*(M2[97]))[110] = M1(4,16); (*(M2[97]))[111] = M1(4,17); (*(M2[97]))[113] = M1(4,18); (*(M2[97]))[119] = M1(4,19); (*(M2[97]))[130] = M1(4,20); (*(M2[97]))[131] = M1(4,21); (*(M2[97]))[133] = M1(4,22); (*(M2[97]))[139] = M1(4,23); (*(M2[98]))[82] = M1(5,5); (*(M2[98]))[85] = M1(5,7); (*(M2[98]))[86] = M1(5,8); (*(M2[98]))[88] = M1(5,9); (*(M2[98]))[97] = M1(5,11); (*(M2[98]))[98] = M1(5,12); (*(M2[98]))[100] = M1(5,13); (*(M2[98]))[101] = M1(5,14); (*(M2[98]))[103] = M1(5,15); (*(M2[98]))[110] = M1(5,16); (*(M2[98]))[111] = M1(5,17); (*(M2[98]))[113] = M1(5,18); (*(M2[98]))[119] = M1(5,19); (*(M2[98]))[130] = M1(5,20); (*(M2[98]))[131] = M1(5,21); (*(M2[98]))[133] = M1(5,22); (*(M2[98]))[139] = M1(5,23); (*(M2[99]))[83] = M1(6,6); (*(M2[99]))[85] = M1(6,7); (*(M2[99]))[86] = M1(6,8); (*(M2[99]))[88] = M1(6,9); (*(M2[99]))[97] = M1(6,11); (*(M2[99]))[98] = M1(6,12); (*(M2[99]))[100] = M1(6,13); (*(M2[99]))[101] = M1(6,14); (*(M2[99]))[103] = M1(6,15); (*(M2[99]))[110] = M1(6,16); (*(M2[99]))[111] = M1(6,17); (*(M2[99]))[113] = M1(6,18); (*(M2[99]))[119] = M1(6,19); (*(M2[99]))[130] = M1(6,20); (*(M2[99]))[131] = M1(6,21); (*(M2[99]))[133] = M1(6,22); (*(M2[99]))[139] = M1(6,23); (*(M2[100]))[96] = M1(7,10); (*(M2[100]))[98] = M1(7,12); (*(M2[100]))[103] = M1(7,15); (*(M2[100]))[119] = M1(7,19); (*(M2[100]))[139] = M1(7,23); (*(M2[101]))[73] = M1(1,1); (*(M2[101]))[82] = M1(1,7); (*(M2[101]))[83] = M1(1,8); (*(M2[101]))[86] = M1(1,9); (*(M2[101]))[93] = M1(1,11); (*(M2[101]))[94] = M1(1,12); (*(M2[101]))[97] = M1(1,13); (*(M2[101]))[98] = M1(1,14); (*(M2[101]))[101] = M1(1,15); (*(M2[101]))[107] = M1(1,16); (*(M2[101]))[108] = M1(1,17); (*(M2[101]))[111] = M1(1,18); (*(M2[101]))[117] = M1(1,19); (*(M2[101]))[127] = M1(1,20); (*(M2[101]))[128] = M1(1,21); (*(M2[101]))[131] = M1(1,22); (*(M2[101]))[137] = M1(1,23); (*(M2[102]))[74] = M1(2,2); (*(M2[102]))[82] = M1(2,7); (*(M2[102]))[83] = M1(2,8); (*(M2[102]))[86] = M1(2,9); (*(M2[102]))[93] = M1(2,11); (*(M2[102]))[94] = M1(2,12); (*(M2[102]))[97] = M1(2,13); (*(M2[102]))[98] = M1(2,14); (*(M2[102]))[101] = M1(2,15); (*(M2[102]))[107] = M1(2,16); (*(M2[102]))[108] = M1(2,17); (*(M2[102]))[111] = M1(2,18); (*(M2[102]))[117] = M1(2,19); (*(M2[102]))[127] = M1(2,20); (*(M2[102]))[128] = M1(2,21); (*(M2[102]))[131] = M1(2,22); (*(M2[102]))[137] = M1(2,23); (*(M2[103]))[77] = M1(4,4); (*(M2[103]))[82] = M1(4,7); (*(M2[103]))[83] = M1(4,8); (*(M2[103]))[86] = M1(4,9); (*(M2[103]))[93] = M1(4,11); (*(M2[103]))[94] = M1(4,12); (*(M2[103]))[97] = M1(4,13); (*(M2[103]))[98] = M1(4,14); (*(M2[103]))[101] = M1(4,15); (*(M2[103]))[107] = M1(4,16); (*(M2[103]))[108] = M1(4,17); (*(M2[103]))[111] = M1(4,18); (*(M2[103]))[117] = M1(4,19); (*(M2[103]))[127] = M1(4,20); (*(M2[103]))[128] = M1(4,21); (*(M2[103]))[131] = M1(4,22); (*(M2[103]))[137] = M1(4,23); (*(M2[104]))[78] = M1(5,5); (*(M2[104]))[82] = M1(5,7); (*(M2[104]))[83] = M1(5,8); (*(M2[104]))[86] = M1(5,9); (*(M2[104]))[93] = M1(5,11); (*(M2[104]))[94] = M1(5,12); (*(M2[104]))[97] = M1(5,13); (*(M2[104]))[98] = M1(5,14); (*(M2[104]))[101] = M1(5,15); (*(M2[104]))[107] = M1(5,16); (*(M2[104]))[108] = M1(5,17); (*(M2[104]))[111] = M1(5,18); (*(M2[104]))[117] = M1(5,19); (*(M2[104]))[127] = M1(5,20); (*(M2[104]))[128] = M1(5,21); (*(M2[104]))[131] = M1(5,22); (*(M2[104]))[137] = M1(5,23); (*(M2[105]))[79] = M1(6,6); (*(M2[105]))[82] = M1(6,7); (*(M2[105]))[83] = M1(6,8); (*(M2[105]))[86] = M1(6,9); (*(M2[105]))[93] = M1(6,11); (*(M2[105]))[94] = M1(6,12); (*(M2[105]))[97] = M1(6,13); (*(M2[105]))[98] = M1(6,14); (*(M2[105]))[101] = M1(6,15); (*(M2[105]))[107] = M1(6,16); (*(M2[105]))[108] = M1(6,17); (*(M2[105]))[111] = M1(6,18); (*(M2[105]))[117] = M1(6,19); (*(M2[105]))[127] = M1(6,20); (*(M2[105]))[128] = M1(6,21); (*(M2[105]))[131] = M1(6,22); (*(M2[105]))[137] = M1(6,23); (*(M2[106]))[92] = M1(7,10); (*(M2[106]))[94] = M1(7,12); (*(M2[106]))[101] = M1(7,15); (*(M2[106]))[117] = M1(7,19); (*(M2[106]))[137] = M1(7,23); (*(M2[107]))[92] = M1(2,2); (*(M2[107]))[99] = M1(2,7); (*(M2[107]))[100] = M1(2,8); (*(M2[107]))[102] = M1(2,9); (*(M2[107]))[106] = M1(2,11); (*(M2[107]))[107] = M1(2,12); (*(M2[107]))[109] = M1(2,13); (*(M2[107]))[110] = M1(2,14); (*(M2[107]))[112] = M1(2,15); (*(M2[107]))[115] = M1(2,16); (*(M2[107]))[116] = M1(2,17); (*(M2[107]))[118] = M1(2,18); (*(M2[107]))[121] = M1(2,19); (*(M2[107]))[135] = M1(2,20); (*(M2[107]))[136] = M1(2,21); (*(M2[107]))[138] = M1(2,22); (*(M2[107]))[141] = M1(2,23); (*(M2[108]))[93] = M1(3,3); (*(M2[108]))[99] = M1(3,7); (*(M2[108]))[100] = M1(3,8); (*(M2[108]))[102] = M1(3,9); (*(M2[108]))[106] = M1(3,11); (*(M2[108]))[107] = M1(3,12); (*(M2[108]))[109] = M1(3,13); (*(M2[108]))[110] = M1(3,14); (*(M2[108]))[112] = M1(3,15); (*(M2[108]))[115] = M1(3,16); (*(M2[108]))[116] = M1(3,17); (*(M2[108]))[118] = M1(3,18); (*(M2[108]))[121] = M1(3,19); (*(M2[108]))[135] = M1(3,20); (*(M2[108]))[136] = M1(3,21); (*(M2[108]))[138] = M1(3,22); (*(M2[108]))[141] = M1(3,23); (*(M2[109]))[96] = M1(5,5); (*(M2[109]))[99] = M1(5,7); (*(M2[109]))[100] = M1(5,8); (*(M2[109]))[102] = M1(5,9); (*(M2[109]))[106] = M1(5,11); (*(M2[109]))[107] = M1(5,12); (*(M2[109]))[109] = M1(5,13); (*(M2[109]))[110] = M1(5,14); (*(M2[109]))[112] = M1(5,15); (*(M2[109]))[115] = M1(5,16); (*(M2[109]))[116] = M1(5,17); (*(M2[109]))[118] = M1(5,18); (*(M2[109]))[121] = M1(5,19); (*(M2[109]))[135] = M1(5,20); (*(M2[109]))[136] = M1(5,21); (*(M2[109]))[138] = M1(5,22); (*(M2[109]))[141] = M1(5,23); (*(M2[110]))[97] = M1(6,6); (*(M2[110]))[99] = M1(6,7); (*(M2[110]))[100] = M1(6,8); (*(M2[110]))[102] = M1(6,9); (*(M2[110]))[106] = M1(6,11); (*(M2[110]))[107] = M1(6,12); (*(M2[110]))[109] = M1(6,13); (*(M2[110]))[110] = M1(6,14); (*(M2[110]))[112] = M1(6,15); (*(M2[110]))[115] = M1(6,16); (*(M2[110]))[116] = M1(6,17); (*(M2[110]))[118] = M1(6,18); (*(M2[110]))[121] = M1(6,19); (*(M2[110]))[135] = M1(6,20); (*(M2[110]))[136] = M1(6,21); (*(M2[110]))[138] = M1(6,22); (*(M2[110]))[141] = M1(6,23); (*(M2[111]))[105] = M1(7,10); (*(M2[111]))[107] = M1(7,12); (*(M2[111]))[112] = M1(7,15); (*(M2[111]))[121] = M1(7,19); (*(M2[111]))[141] = M1(7,23); (*(M2[112]))[77] = M1(2,2); (*(M2[112]))[84] = M1(2,7); (*(M2[112]))[85] = M1(2,8); (*(M2[112]))[87] = M1(2,9); (*(M2[112]))[96] = M1(2,11); (*(M2[112]))[97] = M1(2,12); (*(M2[112]))[99] = M1(2,13); (*(M2[112]))[100] = M1(2,14); (*(M2[112]))[102] = M1(2,15); (*(M2[112]))[109] = M1(2,16); (*(M2[112]))[110] = M1(2,17); (*(M2[112]))[112] = M1(2,18); (*(M2[112]))[118] = M1(2,19); (*(M2[112]))[129] = M1(2,20); (*(M2[112]))[130] = M1(2,21); (*(M2[112]))[132] = M1(2,22); (*(M2[112]))[138] = M1(2,23); (*(M2[113]))[78] = M1(3,3); (*(M2[113]))[84] = M1(3,7); (*(M2[113]))[85] = M1(3,8); (*(M2[113]))[87] = M1(3,9); (*(M2[113]))[96] = M1(3,11); (*(M2[113]))[97] = M1(3,12); (*(M2[113]))[99] = M1(3,13); (*(M2[113]))[100] = M1(3,14); (*(M2[113]))[102] = M1(3,15); (*(M2[113]))[109] = M1(3,16); (*(M2[113]))[110] = M1(3,17); (*(M2[113]))[112] = M1(3,18); (*(M2[113]))[118] = M1(3,19); (*(M2[113]))[129] = M1(3,20); (*(M2[113]))[130] = M1(3,21); (*(M2[113]))[132] = M1(3,22); (*(M2[113]))[138] = M1(3,23); (*(M2[114]))[80] = M1(4,4); (*(M2[114]))[84] = M1(4,7); (*(M2[114]))[85] = M1(4,8); (*(M2[114]))[87] = M1(4,9); (*(M2[114]))[96] = M1(4,11); (*(M2[114]))[97] = M1(4,12); (*(M2[114]))[99] = M1(4,13); (*(M2[114]))[100] = M1(4,14); (*(M2[114]))[102] = M1(4,15); (*(M2[114]))[109] = M1(4,16); (*(M2[114]))[110] = M1(4,17); (*(M2[114]))[112] = M1(4,18); (*(M2[114]))[118] = M1(4,19); (*(M2[114]))[129] = M1(4,20); (*(M2[114]))[130] = M1(4,21); (*(M2[114]))[132] = M1(4,22); (*(M2[114]))[138] = M1(4,23); (*(M2[115]))[81] = M1(5,5); (*(M2[115]))[84] = M1(5,7); (*(M2[115]))[85] = M1(5,8); (*(M2[115]))[87] = M1(5,9); (*(M2[115]))[96] = M1(5,11); (*(M2[115]))[97] = M1(5,12); (*(M2[115]))[99] = M1(5,13); (*(M2[115]))[100] = M1(5,14); (*(M2[115]))[102] = M1(5,15); (*(M2[115]))[109] = M1(5,16); (*(M2[115]))[110] = M1(5,17); (*(M2[115]))[112] = M1(5,18); (*(M2[115]))[118] = M1(5,19); (*(M2[115]))[129] = M1(5,20); (*(M2[115]))[130] = M1(5,21); (*(M2[115]))[132] = M1(5,22); (*(M2[115]))[138] = M1(5,23); (*(M2[116]))[82] = M1(6,6); (*(M2[116]))[84] = M1(6,7); (*(M2[116]))[85] = M1(6,8); (*(M2[116]))[87] = M1(6,9); (*(M2[116]))[96] = M1(6,11); (*(M2[116]))[97] = M1(6,12); (*(M2[116]))[99] = M1(6,13); (*(M2[116]))[100] = M1(6,14); (*(M2[116]))[102] = M1(6,15); (*(M2[116]))[109] = M1(6,16); (*(M2[116]))[110] = M1(6,17); (*(M2[116]))[112] = M1(6,18); (*(M2[116]))[118] = M1(6,19); (*(M2[116]))[129] = M1(6,20); (*(M2[116]))[130] = M1(6,21); (*(M2[116]))[132] = M1(6,22); (*(M2[116]))[138] = M1(6,23); (*(M2[117]))[95] = M1(7,10); (*(M2[117]))[97] = M1(7,12); (*(M2[117]))[102] = M1(7,15); (*(M2[117]))[118] = M1(7,19); (*(M2[117]))[138] = M1(7,23); (*(M2[118]))[72] = M1(1,1); (*(M2[118]))[81] = M1(1,7); (*(M2[118]))[82] = M1(1,8); (*(M2[118]))[85] = M1(1,9); (*(M2[118]))[92] = M1(1,11); (*(M2[118]))[93] = M1(1,12); (*(M2[118]))[96] = M1(1,13); (*(M2[118]))[97] = M1(1,14); (*(M2[118]))[100] = M1(1,15); (*(M2[118]))[106] = M1(1,16); (*(M2[118]))[107] = M1(1,17); (*(M2[118]))[110] = M1(1,18); (*(M2[118]))[116] = M1(1,19); (*(M2[118]))[126] = M1(1,20); (*(M2[118]))[127] = M1(1,21); (*(M2[118]))[130] = M1(1,22); (*(M2[118]))[136] = M1(1,23); (*(M2[119]))[73] = M1(2,2); (*(M2[119]))[81] = M1(2,7); (*(M2[119]))[82] = M1(2,8); (*(M2[119]))[85] = M1(2,9); (*(M2[119]))[92] = M1(2,11); (*(M2[119]))[93] = M1(2,12); (*(M2[119]))[96] = M1(2,13); (*(M2[119]))[97] = M1(2,14); (*(M2[119]))[100] = M1(2,15); (*(M2[119]))[106] = M1(2,16); (*(M2[119]))[107] = M1(2,17); (*(M2[119]))[110] = M1(2,18); (*(M2[119]))[116] = M1(2,19); (*(M2[119]))[126] = M1(2,20); (*(M2[119]))[127] = M1(2,21); (*(M2[119]))[130] = M1(2,22); (*(M2[119]))[136] = M1(2,23); (*(M2[120]))[74] = M1(3,3); (*(M2[120]))[81] = M1(3,7); (*(M2[120]))[82] = M1(3,8); (*(M2[120]))[85] = M1(3,9); (*(M2[120]))[92] = M1(3,11); (*(M2[120]))[93] = M1(3,12); (*(M2[120]))[96] = M1(3,13); (*(M2[120]))[97] = M1(3,14); (*(M2[120]))[100] = M1(3,15); (*(M2[120]))[106] = M1(3,16); (*(M2[120]))[107] = M1(3,17); (*(M2[120]))[110] = M1(3,18); (*(M2[120]))[116] = M1(3,19); (*(M2[120]))[126] = M1(3,20); (*(M2[120]))[127] = M1(3,21); (*(M2[120]))[130] = M1(3,22); (*(M2[120]))[136] = M1(3,23); (*(M2[121]))[76] = M1(4,4); (*(M2[121]))[81] = M1(4,7); (*(M2[121]))[82] = M1(4,8); (*(M2[121]))[85] = M1(4,9); (*(M2[121]))[92] = M1(4,11); (*(M2[121]))[93] = M1(4,12); (*(M2[121]))[96] = M1(4,13); (*(M2[121]))[97] = M1(4,14); (*(M2[121]))[100] = M1(4,15); (*(M2[121]))[106] = M1(4,16); (*(M2[121]))[107] = M1(4,17); (*(M2[121]))[110] = M1(4,18); (*(M2[121]))[116] = M1(4,19); (*(M2[121]))[126] = M1(4,20); (*(M2[121]))[127] = M1(4,21); (*(M2[121]))[130] = M1(4,22); (*(M2[121]))[136] = M1(4,23); (*(M2[122]))[77] = M1(5,5); (*(M2[122]))[81] = M1(5,7); (*(M2[122]))[82] = M1(5,8); (*(M2[122]))[85] = M1(5,9); (*(M2[122]))[92] = M1(5,11); (*(M2[122]))[93] = M1(5,12); (*(M2[122]))[96] = M1(5,13); (*(M2[122]))[97] = M1(5,14); (*(M2[122]))[100] = M1(5,15); (*(M2[122]))[106] = M1(5,16); (*(M2[122]))[107] = M1(5,17); (*(M2[122]))[110] = M1(5,18); (*(M2[122]))[116] = M1(5,19); (*(M2[122]))[126] = M1(5,20); (*(M2[122]))[127] = M1(5,21); (*(M2[122]))[130] = M1(5,22); (*(M2[122]))[136] = M1(5,23); (*(M2[123]))[78] = M1(6,6); (*(M2[123]))[81] = M1(6,7); (*(M2[123]))[82] = M1(6,8); (*(M2[123]))[85] = M1(6,9); (*(M2[123]))[92] = M1(6,11); (*(M2[123]))[93] = M1(6,12); (*(M2[123]))[96] = M1(6,13); (*(M2[123]))[97] = M1(6,14); (*(M2[123]))[100] = M1(6,15); (*(M2[123]))[106] = M1(6,16); (*(M2[123]))[107] = M1(6,17); (*(M2[123]))[110] = M1(6,18); (*(M2[123]))[116] = M1(6,19); (*(M2[123]))[126] = M1(6,20); (*(M2[123]))[127] = M1(6,21); (*(M2[123]))[130] = M1(6,22); (*(M2[123]))[136] = M1(6,23); (*(M2[124]))[91] = M1(7,10); (*(M2[124]))[93] = M1(7,12); (*(M2[124]))[100] = M1(7,15); (*(M2[124]))[116] = M1(7,19); (*(M2[124]))[136] = M1(7,23); (*(M2[125]))[70] = M1(0,0); (*(M2[125]))[80] = M1(0,7); (*(M2[125]))[81] = M1(0,8); (*(M2[125]))[84] = M1(0,9); (*(M2[125]))[91] = M1(0,11); (*(M2[125]))[92] = M1(0,12); (*(M2[125]))[95] = M1(0,13); (*(M2[125]))[96] = M1(0,14); (*(M2[125]))[99] = M1(0,15); (*(M2[125]))[105] = M1(0,16); (*(M2[125]))[106] = M1(0,17); (*(M2[125]))[109] = M1(0,18); (*(M2[125]))[115] = M1(0,19); (*(M2[125]))[125] = M1(0,20); (*(M2[125]))[126] = M1(0,21); (*(M2[125]))[129] = M1(0,22); (*(M2[125]))[135] = M1(0,23); (*(M2[126]))[71] = M1(1,1); (*(M2[126]))[80] = M1(1,7); (*(M2[126]))[81] = M1(1,8); (*(M2[126]))[84] = M1(1,9); (*(M2[126]))[91] = M1(1,11); (*(M2[126]))[92] = M1(1,12); (*(M2[126]))[95] = M1(1,13); (*(M2[126]))[96] = M1(1,14); (*(M2[126]))[99] = M1(1,15); (*(M2[126]))[105] = M1(1,16); (*(M2[126]))[106] = M1(1,17); (*(M2[126]))[109] = M1(1,18); (*(M2[126]))[115] = M1(1,19); (*(M2[126]))[125] = M1(1,20); (*(M2[126]))[126] = M1(1,21); (*(M2[126]))[129] = M1(1,22); (*(M2[126]))[135] = M1(1,23); (*(M2[127]))[72] = M1(2,2); (*(M2[127]))[80] = M1(2,7); (*(M2[127]))[81] = M1(2,8); (*(M2[127]))[84] = M1(2,9); (*(M2[127]))[91] = M1(2,11); (*(M2[127]))[92] = M1(2,12); (*(M2[127]))[95] = M1(2,13); (*(M2[127]))[96] = M1(2,14); (*(M2[127]))[99] = M1(2,15); (*(M2[127]))[105] = M1(2,16); (*(M2[127]))[106] = M1(2,17); (*(M2[127]))[109] = M1(2,18); (*(M2[127]))[115] = M1(2,19); (*(M2[127]))[125] = M1(2,20); (*(M2[127]))[126] = M1(2,21); (*(M2[127]))[129] = M1(2,22); (*(M2[127]))[135] = M1(2,23); (*(M2[128]))[73] = M1(3,3); (*(M2[128]))[80] = M1(3,7); (*(M2[128]))[81] = M1(3,8); (*(M2[128]))[84] = M1(3,9); (*(M2[128]))[91] = M1(3,11); (*(M2[128]))[92] = M1(3,12); (*(M2[128]))[95] = M1(3,13); (*(M2[128]))[96] = M1(3,14); (*(M2[128]))[99] = M1(3,15); (*(M2[128]))[105] = M1(3,16); (*(M2[128]))[106] = M1(3,17); (*(M2[128]))[109] = M1(3,18); (*(M2[128]))[115] = M1(3,19); (*(M2[128]))[125] = M1(3,20); (*(M2[128]))[126] = M1(3,21); (*(M2[128]))[129] = M1(3,22); (*(M2[128]))[135] = M1(3,23); (*(M2[129]))[75] = M1(4,4); (*(M2[129]))[80] = M1(4,7); (*(M2[129]))[81] = M1(4,8); (*(M2[129]))[84] = M1(4,9); (*(M2[129]))[91] = M1(4,11); (*(M2[129]))[92] = M1(4,12); (*(M2[129]))[95] = M1(4,13); (*(M2[129]))[96] = M1(4,14); (*(M2[129]))[99] = M1(4,15); (*(M2[129]))[105] = M1(4,16); (*(M2[129]))[106] = M1(4,17); (*(M2[129]))[109] = M1(4,18); (*(M2[129]))[115] = M1(4,19); (*(M2[129]))[125] = M1(4,20); (*(M2[129]))[126] = M1(4,21); (*(M2[129]))[129] = M1(4,22); (*(M2[129]))[135] = M1(4,23); (*(M2[130]))[76] = M1(5,5); (*(M2[130]))[80] = M1(5,7); (*(M2[130]))[81] = M1(5,8); (*(M2[130]))[84] = M1(5,9); (*(M2[130]))[91] = M1(5,11); (*(M2[130]))[92] = M1(5,12); (*(M2[130]))[95] = M1(5,13); (*(M2[130]))[96] = M1(5,14); (*(M2[130]))[99] = M1(5,15); (*(M2[130]))[105] = M1(5,16); (*(M2[130]))[106] = M1(5,17); (*(M2[130]))[109] = M1(5,18); (*(M2[130]))[115] = M1(5,19); (*(M2[130]))[125] = M1(5,20); (*(M2[130]))[126] = M1(5,21); (*(M2[130]))[129] = M1(5,22); (*(M2[130]))[135] = M1(5,23); (*(M2[131]))[77] = M1(6,6); (*(M2[131]))[80] = M1(6,7); (*(M2[131]))[81] = M1(6,8); (*(M2[131]))[84] = M1(6,9); (*(M2[131]))[91] = M1(6,11); (*(M2[131]))[92] = M1(6,12); (*(M2[131]))[95] = M1(6,13); (*(M2[131]))[96] = M1(6,14); (*(M2[131]))[99] = M1(6,15); (*(M2[131]))[105] = M1(6,16); (*(M2[131]))[106] = M1(6,17); (*(M2[131]))[109] = M1(6,18); (*(M2[131]))[115] = M1(6,19); (*(M2[131]))[125] = M1(6,20); (*(M2[131]))[126] = M1(6,21); (*(M2[131]))[129] = M1(6,22); (*(M2[131]))[135] = M1(6,23); (*(M2[132]))[90] = M1(7,10); (*(M2[132]))[92] = M1(7,12); (*(M2[132]))[99] = M1(7,15); (*(M2[132]))[115] = M1(7,19); (*(M2[132]))[135] = M1(7,23); (*(M2[133]))[125] = M1(0,0); (*(M2[133]))[132] = M1(0,7); (*(M2[133]))[133] = M1(0,8); (*(M2[133]))[134] = M1(0,9); (*(M2[133]))[136] = M1(0,11); (*(M2[133]))[137] = M1(0,12); (*(M2[133]))[138] = M1(0,13); (*(M2[133]))[139] = M1(0,14); (*(M2[133]))[140] = M1(0,15); (*(M2[133]))[141] = M1(0,16); (*(M2[133]))[142] = M1(0,17); (*(M2[133]))[143] = M1(0,18); (*(M2[133]))[144] = M1(0,19); (*(M2[133]))[145] = M1(0,20); (*(M2[133]))[146] = M1(0,21); (*(M2[133]))[147] = M1(0,22); (*(M2[133]))[148] = M1(0,23); (*(M2[134]))[126] = M1(1,1); (*(M2[134]))[132] = M1(1,7); (*(M2[134]))[133] = M1(1,8); (*(M2[134]))[134] = M1(1,9); (*(M2[134]))[136] = M1(1,11); (*(M2[134]))[137] = M1(1,12); (*(M2[134]))[138] = M1(1,13); (*(M2[134]))[139] = M1(1,14); (*(M2[134]))[140] = M1(1,15); (*(M2[134]))[141] = M1(1,16); (*(M2[134]))[142] = M1(1,17); (*(M2[134]))[143] = M1(1,18); (*(M2[134]))[144] = M1(1,19); (*(M2[134]))[145] = M1(1,20); (*(M2[134]))[146] = M1(1,21); (*(M2[134]))[147] = M1(1,22); (*(M2[134]))[148] = M1(1,23); (*(M2[135]))[127] = M1(2,2); (*(M2[135]))[132] = M1(2,7); (*(M2[135]))[133] = M1(2,8); (*(M2[135]))[134] = M1(2,9); (*(M2[135]))[136] = M1(2,11); (*(M2[135]))[137] = M1(2,12); (*(M2[135]))[138] = M1(2,13); (*(M2[135]))[139] = M1(2,14); (*(M2[135]))[140] = M1(2,15); (*(M2[135]))[141] = M1(2,16); (*(M2[135]))[142] = M1(2,17); (*(M2[135]))[143] = M1(2,18); (*(M2[135]))[144] = M1(2,19); (*(M2[135]))[145] = M1(2,20); (*(M2[135]))[146] = M1(2,21); (*(M2[135]))[147] = M1(2,22); (*(M2[135]))[148] = M1(2,23); (*(M2[136]))[128] = M1(3,3); (*(M2[136]))[132] = M1(3,7); (*(M2[136]))[133] = M1(3,8); (*(M2[136]))[134] = M1(3,9); (*(M2[136]))[136] = M1(3,11); (*(M2[136]))[137] = M1(3,12); (*(M2[136]))[138] = M1(3,13); (*(M2[136]))[139] = M1(3,14); (*(M2[136]))[140] = M1(3,15); (*(M2[136]))[141] = M1(3,16); (*(M2[136]))[142] = M1(3,17); (*(M2[136]))[143] = M1(3,18); (*(M2[136]))[144] = M1(3,19); (*(M2[136]))[145] = M1(3,20); (*(M2[136]))[146] = M1(3,21); (*(M2[136]))[147] = M1(3,22); (*(M2[136]))[148] = M1(3,23); (*(M2[137]))[129] = M1(4,4); (*(M2[137]))[132] = M1(4,7); (*(M2[137]))[133] = M1(4,8); (*(M2[137]))[134] = M1(4,9); (*(M2[137]))[136] = M1(4,11); (*(M2[137]))[137] = M1(4,12); (*(M2[137]))[138] = M1(4,13); (*(M2[137]))[139] = M1(4,14); (*(M2[137]))[140] = M1(4,15); (*(M2[137]))[141] = M1(4,16); (*(M2[137]))[142] = M1(4,17); (*(M2[137]))[143] = M1(4,18); (*(M2[137]))[144] = M1(4,19); (*(M2[137]))[145] = M1(4,20); (*(M2[137]))[146] = M1(4,21); (*(M2[137]))[147] = M1(4,22); (*(M2[137]))[148] = M1(4,23); (*(M2[138]))[130] = M1(5,5); (*(M2[138]))[132] = M1(5,7); (*(M2[138]))[133] = M1(5,8); (*(M2[138]))[134] = M1(5,9); (*(M2[138]))[136] = M1(5,11); (*(M2[138]))[137] = M1(5,12); (*(M2[138]))[138] = M1(5,13); (*(M2[138]))[139] = M1(5,14); (*(M2[138]))[140] = M1(5,15); (*(M2[138]))[141] = M1(5,16); (*(M2[138]))[142] = M1(5,17); (*(M2[138]))[143] = M1(5,18); (*(M2[138]))[144] = M1(5,19); (*(M2[138]))[145] = M1(5,20); (*(M2[138]))[146] = M1(5,21); (*(M2[138]))[147] = M1(5,22); (*(M2[138]))[148] = M1(5,23); (*(M2[139]))[131] = M1(6,6); (*(M2[139]))[132] = M1(6,7); (*(M2[139]))[133] = M1(6,8); (*(M2[139]))[134] = M1(6,9); (*(M2[139]))[136] = M1(6,11); (*(M2[139]))[137] = M1(6,12); (*(M2[139]))[138] = M1(6,13); (*(M2[139]))[139] = M1(6,14); (*(M2[139]))[140] = M1(6,15); (*(M2[139]))[141] = M1(6,16); (*(M2[139]))[142] = M1(6,17); (*(M2[139]))[143] = M1(6,18); (*(M2[139]))[144] = M1(6,19); (*(M2[139]))[145] = M1(6,20); (*(M2[139]))[146] = M1(6,21); (*(M2[139]))[147] = M1(6,22); (*(M2[139]))[148] = M1(6,23); (*(M2[140]))[135] = M1(7,10); (*(M2[140]))[137] = M1(7,12); (*(M2[140]))[140] = M1(7,15); (*(M2[140]))[144] = M1(7,19); (*(M2[140]))[148] = M1(7,23); opengv::math::gauss_jordan(M2,121); Action = Eigen::Matrix::Zero(); for( int s = 0; s < 8; s++ ) Action(0,s) -= (*(M2[121]))[141+s]; for( int s = 0; s < 8; s++ ) Action(1,s) -= (*(M2[122]))[141+s]; for( int s = 0; s < 8; s++ ) Action(2,s) -= (*(M2[123]))[141+s]; for( int s = 0; s < 8; s++ ) Action(3,s) -= (*(M2[124]))[141+s]; Action(4,0) = 1.0; Action(5,1) = 1.0; Action(6,2) = 1.0; Action(7,3) = 1.0; //columns of Action mean: // x_1*x_4^2 x_2*x_4^2 x_3*x_4^2 x_4^3 x_1 x_2 x_3 x_4 for( int r = 0; r < 141; r++ ) delete M2[r]; } opengv/src/absolute_pose/modules/gpnp5/0000775016516101651610000000000013344612246017143 5ustar dimadimaopengv/src/absolute_pose/modules/gpnp5/reductors.cpp0000664016516101651610000047324713344612246021702 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp5::groebnerRow6_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,60) / groebnerMatrix(6,60); groebnerMatrix(targetRow,60) = 0.0; groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,61) / groebnerMatrix(7,61); groebnerMatrix(targetRow,61) = 0.0; groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow8_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,62) / groebnerMatrix(8,62); groebnerMatrix(targetRow,62) = 0.0; groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(8,63); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(8,64); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(8,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(8,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(8,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(8,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(8,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(8,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(8,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(8,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(8,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(8,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(8,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(8,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(8,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(8,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(8,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow9_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,63) / groebnerMatrix(9,63); groebnerMatrix(targetRow,63) = 0.0; groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(9,64); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(9,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(9,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(9,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(9,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(9,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(9,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(9,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(9,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(9,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow10_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,33) / groebnerMatrix(10,64); groebnerMatrix(targetRow,33) = 0.0; groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(10,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(10,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(10,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(10,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(10,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(10,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(10,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(10,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(10,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(10,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow6_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,35) / groebnerMatrix(6,60); groebnerMatrix(targetRow,35) = 0.0; groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,36) / groebnerMatrix(7,61); groebnerMatrix(targetRow,36) = 0.0; groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow8_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,37) / groebnerMatrix(8,62); groebnerMatrix(targetRow,37) = 0.0; groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(8,63); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(8,64); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(8,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(8,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(8,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(8,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(8,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(8,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(8,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(8,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(8,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(8,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(8,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(8,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(8,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(8,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(8,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow9_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,38) / groebnerMatrix(9,63); groebnerMatrix(targetRow,38) = 0.0; groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(9,64); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(9,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(9,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(9,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(9,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(9,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(9,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(9,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(9,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(9,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow10_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,39) / groebnerMatrix(10,64); groebnerMatrix(targetRow,39) = 0.0; groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(10,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(10,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(10,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(10,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(10,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(10,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(10,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(10,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(10,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(10,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow6_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,45) / groebnerMatrix(6,60); groebnerMatrix(targetRow,45) = 0.0; groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,46) / groebnerMatrix(7,61); groebnerMatrix(targetRow,46) = 0.0; groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow8_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,47) / groebnerMatrix(8,62); groebnerMatrix(targetRow,47) = 0.0; groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(8,63); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(8,64); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(8,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(8,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(8,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(8,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(8,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(8,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(8,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(8,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(8,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(8,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(8,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(8,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(8,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(8,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(8,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow9_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,48) / groebnerMatrix(9,63); groebnerMatrix(targetRow,48) = 0.0; groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(9,64); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(9,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(9,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(9,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(9,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(9,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(9,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(9,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(9,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(9,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow10_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,49) / groebnerMatrix(10,64); groebnerMatrix(targetRow,49) = 0.0; groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(10,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(10,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(10,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(10,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(10,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(10,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(10,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(10,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(10,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(10,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow10_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,64) / groebnerMatrix(10,64); groebnerMatrix(targetRow,64) = 0.0; groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(10,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(10,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(10,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(10,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(10,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(10,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(10,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(10,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(10,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(10,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow9_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,32) / groebnerMatrix(9,63); groebnerMatrix(targetRow,32) = 0.0; groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(9,64); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(9,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(9,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(9,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(9,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(9,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(9,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(9,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(9,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(9,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow5_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,34) / groebnerMatrix(5,59); groebnerMatrix(targetRow,34) = 0.0; groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(5,60); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(5,61); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(5,62); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(5,63); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(5,64); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(5,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(5,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(5,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(5,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(5,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(5,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(5,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(5,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(5,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(5,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(5,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(5,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(5,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(5,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(5,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow11_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,40) / groebnerMatrix(11,40); groebnerMatrix(targetRow,40) = 0.0; groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(11,41); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(11,42); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(11,43); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(11,50); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(11,51); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(11,52); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(11,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(11,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(11,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(11,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(11,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(11,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(11,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(11,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(11,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(11,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(11,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(11,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(11,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(11,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(11,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(11,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(11,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(11,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(11,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(11,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(11,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow5_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,44) / groebnerMatrix(5,59); groebnerMatrix(targetRow,44) = 0.0; groebnerMatrix(targetRow,45) -= factor * groebnerMatrix(5,60); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(5,61); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(5,62); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(5,63); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(5,64); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(5,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(5,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(5,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(5,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(5,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(5,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(5,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(5,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(5,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(5,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(5,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(5,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(5,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(5,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(5,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow5_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,59) / groebnerMatrix(5,59); groebnerMatrix(targetRow,59) = 0.0; groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(5,60); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(5,61); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(5,62); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(5,63); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(5,64); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(5,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(5,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(5,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(5,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(5,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(5,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(5,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(5,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(5,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(5,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(5,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(5,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(5,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(5,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(5,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow8_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,31) / groebnerMatrix(8,62); groebnerMatrix(targetRow,31) = 0.0; groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(8,63); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(8,64); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(8,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(8,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(8,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(8,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(8,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(8,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(8,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(8,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(8,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(8,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(8,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(8,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(8,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(8,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(8,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow12_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,41) / groebnerMatrix(12,41); groebnerMatrix(targetRow,41) = 0.0; groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(12,42); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(12,43); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(12,50); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(12,51); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(12,52); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(12,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(12,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(12,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(12,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(12,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(12,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(12,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(12,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(12,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(12,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(12,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(12,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(12,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(12,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(12,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(12,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(12,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,30) / groebnerMatrix(7,61); groebnerMatrix(targetRow,30) = 0.0; groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow13_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,42) / groebnerMatrix(13,42); groebnerMatrix(targetRow,42) = 0.0; groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(13,43); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(13,50); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(13,51); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(13,52); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(13,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(13,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(13,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(13,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(13,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(13,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(13,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(13,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(13,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(13,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(13,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(13,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(13,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(13,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(13,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(13,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(13,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(13,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(13,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(13,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(13,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow14_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,43) / groebnerMatrix(14,43); groebnerMatrix(targetRow,43) = 0.0; groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(14,50); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(14,51); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(14,52); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(14,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(14,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(14,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(14,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(14,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(14,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(14,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(14,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(14,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(14,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(14,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(14,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(14,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(14,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(14,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(14,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(14,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(14,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(14,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(14,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(14,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow6_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,29) / groebnerMatrix(6,60); groebnerMatrix(targetRow,29) = 0.0; groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow15_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,50) / groebnerMatrix(15,50); groebnerMatrix(targetRow,50) = 0.0; groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(15,51); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(15,52); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(15,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(15,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(15,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(15,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(15,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(15,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(15,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(15,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(15,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(15,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(15,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(15,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(15,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(15,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(15,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(15,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(15,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(15,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,27) / groebnerMatrix(7,61); groebnerMatrix(targetRow,27) = 0.0; groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,45) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow5_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,28) / groebnerMatrix(5,59); groebnerMatrix(targetRow,28) = 0.0; groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(5,60); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(5,61); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(5,62); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(5,63); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(5,64); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(5,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(5,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(5,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(5,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(5,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(5,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(5,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(5,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(5,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(5,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(5,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(5,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(5,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(5,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(5,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow16_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,51) / groebnerMatrix(16,51); groebnerMatrix(targetRow,51) = 0.0; groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(16,52); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(16,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(16,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(16,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(16,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(16,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(16,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(16,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(16,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(16,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(16,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(16,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(16,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(16,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(16,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(16,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(16,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(16,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(16,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(16,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(16,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(16,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow6_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,26) / groebnerMatrix(6,60); groebnerMatrix(targetRow,26) = 0.0; groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,45) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow17_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,52) / groebnerMatrix(17,52); groebnerMatrix(targetRow,52) = 0.0; groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(17,53); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(17,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(17,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(17,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(17,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(17,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(17,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(17,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(17,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(17,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(17,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(17,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(17,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(17,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(17,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(17,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(17,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(17,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(17,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(17,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(17,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow15_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,17) / groebnerMatrix(15,50); groebnerMatrix(targetRow,17) = 0.0; groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(15,51); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(15,52); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(15,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(15,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(15,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(15,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(15,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(15,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(15,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(15,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(15,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(15,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(15,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(15,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(15,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(15,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(15,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(15,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(15,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(15,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow16_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,18) / groebnerMatrix(16,51); groebnerMatrix(targetRow,18) = 0.0; groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(16,52); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(16,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(16,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(16,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(16,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(16,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(16,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(16,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(16,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(16,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(16,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(16,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(16,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(16,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(16,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(16,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(16,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(16,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(16,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(16,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(16,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(16,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow17_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,19) / groebnerMatrix(17,52); groebnerMatrix(targetRow,19) = 0.0; groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(17,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(17,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(17,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(17,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(17,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(17,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(17,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(17,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(17,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(17,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(17,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(17,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(17,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(17,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(17,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(17,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(17,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(17,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(17,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(17,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(17,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow18_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,20) / groebnerMatrix(18,53); groebnerMatrix(targetRow,20) = 0.0; groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(18,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(18,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(18,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(18,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(18,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(18,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(18,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(18,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(18,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(18,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(18,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(18,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(18,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(18,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(18,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(18,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(18,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(18,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(18,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(18,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow18_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,53) / groebnerMatrix(18,53); groebnerMatrix(targetRow,53) = 0.0; groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(18,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(18,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(18,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(18,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(18,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(18,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(18,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(18,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(18,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(18,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(18,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(18,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(18,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(18,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(18,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(18,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(18,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(18,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(18,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(18,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow14_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,10) / groebnerMatrix(14,43); groebnerMatrix(targetRow,10) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(14,50); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(14,51); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(14,52); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(14,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(14,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(14,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(14,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(14,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(14,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(14,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(14,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(14,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(14,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(14,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(14,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(14,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(14,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(14,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(14,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(14,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(14,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(14,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(14,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(14,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow19_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,21) / groebnerMatrix(19,21); groebnerMatrix(targetRow,21) = 0.0; groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(19,22); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(19,23); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(19,24); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(19,25); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(19,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(19,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(19,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(19,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(19,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(19,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(19,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(19,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(19,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(19,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(19,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(19,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(19,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(19,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(19,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(19,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(19,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(19,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(19,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(19,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow8_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,14) / groebnerMatrix(8,62); groebnerMatrix(targetRow,14) = 0.0; groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(8,63); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(8,64); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(8,65); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(8,66); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(8,67); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(8,68); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(8,69); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(8,70); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(8,71); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(8,72); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(8,73); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(8,74); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(8,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(8,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(8,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(8,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(8,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow9_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,15) / groebnerMatrix(9,63); groebnerMatrix(targetRow,15) = 0.0; groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(9,64); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(9,65); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(9,67); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(9,68); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(9,69); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(9,72); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(9,73); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(9,74); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(9,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(9,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow10_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,16) / groebnerMatrix(10,64); groebnerMatrix(targetRow,16) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(10,65); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(10,66); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(10,67); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(10,68); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(10,69); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(10,72); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(10,73); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(10,74); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(10,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(10,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow20_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,22) / groebnerMatrix(20,22); groebnerMatrix(targetRow,22) = 0.0; groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(20,23); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(20,24); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(20,25); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(20,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(20,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(20,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(20,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(20,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(20,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(20,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(20,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(20,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(20,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(20,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(20,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(20,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(20,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(20,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(20,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(20,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(20,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(20,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(20,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow13_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,9) / groebnerMatrix(13,42); groebnerMatrix(targetRow,9) = 0.0; groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(13,43); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(13,50); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(13,51); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(13,52); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(13,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(13,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(13,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(13,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(13,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(13,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(13,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(13,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(13,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(13,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(13,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(13,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(13,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(13,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(13,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(13,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(13,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(13,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(13,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(13,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(13,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow21_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,23) / groebnerMatrix(21,23); groebnerMatrix(targetRow,23) = 0.0; groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(21,24); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(21,25); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(21,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(21,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(21,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(21,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(21,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(21,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(21,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(21,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(21,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(21,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(21,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(21,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(21,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(21,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(21,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(21,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(21,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(21,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(21,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(21,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow6_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,12) / groebnerMatrix(6,60); groebnerMatrix(targetRow,12) = 0.0; groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,13) / groebnerMatrix(7,61); groebnerMatrix(targetRow,13) = 0.0; groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow22_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,24) / groebnerMatrix(22,24); groebnerMatrix(targetRow,24) = 0.0; groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(22,25); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(22,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(22,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(22,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(22,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(22,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(22,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(22,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(22,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(22,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(22,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(22,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(22,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(22,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(22,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(22,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(22,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(22,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(22,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(22,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(22,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow12_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,8) / groebnerMatrix(12,41); groebnerMatrix(targetRow,8) = 0.0; groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(12,42); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(12,43); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(12,50); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(12,51); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(12,52); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(12,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(12,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(12,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(12,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(12,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(12,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(12,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(12,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(12,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(12,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(12,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(12,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(12,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(12,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(12,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(12,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(12,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow23_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,25) / groebnerMatrix(23,25); groebnerMatrix(targetRow,25) = 0.0; groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(23,54); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(23,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(23,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(23,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(23,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(23,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(23,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(23,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(23,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(23,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(23,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(23,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(23,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(23,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(23,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(23,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(23,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(23,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(23,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(23,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow5_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,11) / groebnerMatrix(5,59); groebnerMatrix(targetRow,11) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(5,60); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(5,61); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(5,62); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(5,63); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(5,64); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(5,65); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(5,66); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(5,67); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(5,68); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(5,69); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(5,70); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(5,71); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(5,72); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(5,73); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(5,74); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(5,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(5,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(5,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(5,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(5,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow24_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,21) / groebnerMatrix(24,54); groebnerMatrix(targetRow,21) = 0.0; groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(24,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(24,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(24,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(24,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(24,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(24,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(24,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(24,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(24,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(24,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(24,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(24,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(24,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(24,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(24,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(24,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(24,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(24,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(24,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow24_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,54) / groebnerMatrix(24,54); groebnerMatrix(targetRow,54) = 0.0; groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(24,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(24,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(24,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(24,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(24,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(24,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(24,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(24,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(24,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(24,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(24,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(24,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(24,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(24,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(24,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(24,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(24,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(24,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(24,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow11_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,7) / groebnerMatrix(11,40); groebnerMatrix(targetRow,7) = 0.0; groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(11,41); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(11,42); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(11,43); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(11,50); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(11,51); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(11,52); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(11,53); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(11,54); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(11,55); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(11,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(11,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(11,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(11,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(11,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(11,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(11,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(11,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(11,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(11,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(11,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(11,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(11,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(11,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(11,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(11,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(11,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(11,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow25_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,22) / groebnerMatrix(25,55); groebnerMatrix(targetRow,22) = 0.0; groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(25,56); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(25,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(25,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(25,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(25,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(25,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(25,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(25,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(25,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(25,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(25,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(25,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(25,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(25,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(25,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(25,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(25,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(25,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow25_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,55) / groebnerMatrix(25,55); groebnerMatrix(targetRow,55) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(25,56); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(25,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(25,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(25,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(25,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(25,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(25,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(25,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(25,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(25,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(25,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(25,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(25,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(25,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(25,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(25,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(25,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(25,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow10_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,6) / groebnerMatrix(10,64); groebnerMatrix(targetRow,6) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(10,65); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(10,66); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(10,67); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(10,68); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(10,69); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(10,72); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(10,73); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(10,74); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(10,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(10,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow26_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,23) / groebnerMatrix(26,56); groebnerMatrix(targetRow,23) = 0.0; groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(26,57); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(26,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(26,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(26,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(26,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(26,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(26,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(26,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(26,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(26,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(26,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(26,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(26,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(26,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(26,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(26,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(26,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow26_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,56) / groebnerMatrix(26,56); groebnerMatrix(targetRow,56) = 0.0; groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(26,57); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(26,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(26,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(26,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(26,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(26,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(26,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(26,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(26,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(26,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(26,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(26,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(26,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(26,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(26,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(26,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(26,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow27_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,24) / groebnerMatrix(27,57); groebnerMatrix(targetRow,24) = 0.0; groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(27,58); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(27,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(27,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(27,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(27,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(27,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(27,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(27,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(27,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(27,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(27,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(27,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(27,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(27,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(27,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(27,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow27_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,57) / groebnerMatrix(27,57); groebnerMatrix(targetRow,57) = 0.0; groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(27,58); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(27,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(27,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(27,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(27,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(27,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(27,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(27,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(27,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(27,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(27,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(27,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(27,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(27,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(27,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(27,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow9_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,5) / groebnerMatrix(9,63); groebnerMatrix(targetRow,5) = 0.0; groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(9,64); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(9,65); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(9,67); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(9,68); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(9,69); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(9,72); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(9,73); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(9,74); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(9,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(9,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow28_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,25) / groebnerMatrix(28,58); groebnerMatrix(targetRow,25) = 0.0; groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(28,65); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(28,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(28,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(28,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(28,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(28,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(28,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(28,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(28,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(28,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(28,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(28,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(28,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(28,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(28,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow28_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,58) / groebnerMatrix(28,58); groebnerMatrix(targetRow,58) = 0.0; groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(28,65); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(28,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(28,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(28,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(28,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(28,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(28,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(28,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(28,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(28,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(28,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(28,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(28,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(28,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(28,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow18_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,7) / groebnerMatrix(18,53); groebnerMatrix(targetRow,7) = 0.0; groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(18,54); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(18,55); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(18,56); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(18,57); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(18,58); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(18,65); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(18,66); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(18,67); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(18,68); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(18,69); groebnerMatrix(targetRow,45) -= factor * groebnerMatrix(18,70); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(18,71); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(18,72); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(18,73); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(18,74); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(18,75); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(18,76); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(18,77); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(18,78); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(18,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow24_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,17) / groebnerMatrix(24,54); groebnerMatrix(targetRow,17) = 0.0; groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(24,55); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(24,56); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(24,57); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(24,58); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(24,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(24,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(24,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(24,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(24,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(24,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(24,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(24,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(24,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(24,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(24,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(24,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(24,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(24,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(24,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow29_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,40) / groebnerMatrix(29,65); groebnerMatrix(targetRow,40) = 0.0; groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(29,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(29,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(29,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(29,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(29,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(29,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(29,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(29,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(29,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(29,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(29,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(29,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(29,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(29,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow29_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,50) / groebnerMatrix(29,65); groebnerMatrix(targetRow,50) = 0.0; groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(29,66); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(29,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(29,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(29,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(29,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(29,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(29,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(29,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(29,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(29,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(29,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(29,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(29,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(29,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow29_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,65) / groebnerMatrix(29,65); groebnerMatrix(targetRow,65) = 0.0; groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(29,66); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(29,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(29,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(29,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(29,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(29,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(29,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(29,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(29,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(29,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(29,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(29,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(29,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(29,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow14_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(14,43); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(14,50); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(14,51); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(14,52); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(14,53); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(14,54); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(14,55); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(14,56); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(14,57); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(14,58); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(14,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(14,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(14,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(14,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(14,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(14,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(14,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(14,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(14,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(14,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(14,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(14,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(14,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(14,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(14,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow8_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,4) / groebnerMatrix(8,62); groebnerMatrix(targetRow,4) = 0.0; groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(8,63); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(8,64); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(8,65); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(8,66); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(8,67); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(8,68); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(8,69); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(8,70); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(8,71); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(8,72); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(8,73); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(8,74); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(8,75); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(8,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(8,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(8,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(8,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow18_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,8) / groebnerMatrix(18,53); groebnerMatrix(targetRow,8) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(18,54); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(18,55); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(18,56); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(18,57); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(18,58); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(18,65); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(18,66); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(18,67); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(18,68); groebnerMatrix(targetRow,45) -= factor * groebnerMatrix(18,69); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(18,70); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(18,71); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(18,72); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(18,73); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(18,74); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(18,75); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(18,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(18,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(18,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(18,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow25_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,18) / groebnerMatrix(25,55); groebnerMatrix(targetRow,18) = 0.0; groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(25,56); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(25,57); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(25,58); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(25,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(25,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(25,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(25,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(25,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(25,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(25,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(25,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(25,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(25,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(25,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(25,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(25,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(25,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(25,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow30_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,41) / groebnerMatrix(30,66); groebnerMatrix(targetRow,41) = 0.0; groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(30,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(30,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(30,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(30,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(30,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(30,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(30,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(30,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(30,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(30,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(30,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(30,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(30,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow30_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,51) / groebnerMatrix(30,66); groebnerMatrix(targetRow,51) = 0.0; groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(30,67); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(30,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(30,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(30,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(30,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(30,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(30,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(30,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(30,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(30,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(30,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(30,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(30,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow30_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,66) / groebnerMatrix(30,66); groebnerMatrix(targetRow,66) = 0.0; groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(30,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(30,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(30,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(30,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(30,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(30,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(30,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(30,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(30,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(30,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(30,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(30,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(30,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow14_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,0) / groebnerMatrix(14,43); groebnerMatrix(targetRow,0) = 0.0; groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(14,50); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(14,51); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(14,52); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(14,53); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(14,54); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(14,55); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(14,56); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(14,57); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(14,58); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(14,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(14,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(14,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(14,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(14,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(14,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(14,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(14,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(14,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(14,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(14,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(14,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(14,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(14,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(14,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow6_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,2) / groebnerMatrix(6,60); groebnerMatrix(targetRow,2) = 0.0; groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(6,61); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(6,62); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(6,63); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(6,64); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(6,65); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(6,66); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(6,67); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(6,68); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(6,69); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(6,70); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(6,71); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(6,72); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(6,73); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(6,74); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(6,75); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(6,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(6,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(6,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(6,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow7_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,3) / groebnerMatrix(7,61); groebnerMatrix(targetRow,3) = 0.0; groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(7,62); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(7,63); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(7,64); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(7,65); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(7,66); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(7,67); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(7,68); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(7,69); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(7,70); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(7,71); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(7,72); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(7,73); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(7,74); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(7,75); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(7,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(7,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(7,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(7,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow18_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,9) / groebnerMatrix(18,53); groebnerMatrix(targetRow,9) = 0.0; groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(18,54); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(18,55); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(18,56); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(18,57); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(18,58); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(18,65); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(18,66); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(18,67); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(18,68); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(18,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(18,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(18,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(18,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(18,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(18,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(18,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(18,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(18,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(18,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(18,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow26_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,19) / groebnerMatrix(26,56); groebnerMatrix(targetRow,19) = 0.0; groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(26,57); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(26,58); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(26,65); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(26,66); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(26,67); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(26,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(26,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(26,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(26,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(26,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(26,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(26,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(26,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(26,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(26,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(26,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(26,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow31_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,42) / groebnerMatrix(31,67); groebnerMatrix(targetRow,42) = 0.0; groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(31,68); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(31,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(31,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(31,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(31,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(31,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(31,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(31,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(31,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(31,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(31,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(31,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow31_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,52) / groebnerMatrix(31,67); groebnerMatrix(targetRow,52) = 0.0; groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(31,68); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(31,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(31,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(31,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(31,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(31,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(31,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(31,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(31,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(31,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(31,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(31,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow31_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,67) / groebnerMatrix(31,67); groebnerMatrix(targetRow,67) = 0.0; groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(31,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(31,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(31,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(31,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(31,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(31,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(31,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(31,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(31,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(31,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(31,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(31,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow32_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,68) / groebnerMatrix(32,68); groebnerMatrix(targetRow,68) = 0.0; groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(32,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(32,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(32,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow32_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,53) / groebnerMatrix(32,68); groebnerMatrix(targetRow,53) = 0.0; groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(32,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(32,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(32,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow33_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,54) / groebnerMatrix(33,69); groebnerMatrix(targetRow,54) = 0.0; groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(33,70); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(33,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(33,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow33_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,69) / groebnerMatrix(33,69); groebnerMatrix(targetRow,69) = 0.0; groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(33,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(33,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(33,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow34_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,55) / groebnerMatrix(34,70); groebnerMatrix(targetRow,55) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(34,71); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(34,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(34,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(34,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(34,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(34,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(34,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(34,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(34,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow34_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,70) / groebnerMatrix(34,70); groebnerMatrix(targetRow,70) = 0.0; groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(34,71); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(34,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(34,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(34,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(34,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(34,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(34,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(34,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(34,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow35_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,56) / groebnerMatrix(35,71); groebnerMatrix(targetRow,56) = 0.0; groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(35,72); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(35,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(35,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(35,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(35,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(35,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(35,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(35,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow35_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,71) / groebnerMatrix(35,71); groebnerMatrix(targetRow,71) = 0.0; groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(35,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(35,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(35,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(35,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(35,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(35,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(35,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(35,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow36_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,57) / groebnerMatrix(36,72); groebnerMatrix(targetRow,57) = 0.0; groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(36,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow36_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,72) / groebnerMatrix(36,72); groebnerMatrix(targetRow,72) = 0.0; groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(36,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow32_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,43) / groebnerMatrix(32,68); groebnerMatrix(targetRow,43) = 0.0; groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(32,70); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(32,71); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(32,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow37_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,58) / groebnerMatrix(37,73); groebnerMatrix(targetRow,58) = 0.0; groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(37,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow37_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,73) / groebnerMatrix(37,73); groebnerMatrix(targetRow,73) = 0.0; groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(37,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow35_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,47) / groebnerMatrix(35,71); groebnerMatrix(targetRow,47) = 0.0; groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(35,72); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(35,73); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(35,74); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(35,75); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(35,76); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(35,77); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(35,78); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(35,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow36_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,50) / groebnerMatrix(36,72); groebnerMatrix(targetRow,50) = 0.0; groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(36,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow37_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,54) / groebnerMatrix(37,73); groebnerMatrix(targetRow,54) = 0.0; groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(37,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_00001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,59) / groebnerMatrix(38,74); groebnerMatrix(targetRow,59) = 0.0; groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,60) / groebnerMatrix(38,74); groebnerMatrix(targetRow,60) = 0.0; groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,62) / groebnerMatrix(38,74); groebnerMatrix(targetRow,62) = 0.0; groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,65) / groebnerMatrix(38,74); groebnerMatrix(targetRow,65) = 0.0; groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,69) / groebnerMatrix(38,74); groebnerMatrix(targetRow,69) = 0.0; groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,74) / groebnerMatrix(38,74); groebnerMatrix(targetRow,74) = 0.0; groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow36_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,51) / groebnerMatrix(36,72); groebnerMatrix(targetRow,51) = 0.0; groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(36,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow37_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,55) / groebnerMatrix(37,73); groebnerMatrix(targetRow,55) = 0.0; groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(37,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_00010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,61) / groebnerMatrix(39,75); groebnerMatrix(targetRow,61) = 0.0; groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,63) / groebnerMatrix(39,75); groebnerMatrix(targetRow,63) = 0.0; groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,66) / groebnerMatrix(39,75); groebnerMatrix(targetRow,66) = 0.0; groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,70) / groebnerMatrix(39,75); groebnerMatrix(targetRow,70) = 0.0; groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,75) / groebnerMatrix(39,75); groebnerMatrix(targetRow,75) = 0.0; groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow32_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,42) / groebnerMatrix(32,68); groebnerMatrix(targetRow,42) = 0.0; groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(32,70); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(32,71); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(32,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_10010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,45) / groebnerMatrix(38,74); groebnerMatrix(targetRow,45) = 0.0; groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_10010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,46) / groebnerMatrix(39,75); groebnerMatrix(targetRow,46) = 0.0; groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_10100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,47) / groebnerMatrix(38,74); groebnerMatrix(targetRow,47) = 0.0; groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_10100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,48) / groebnerMatrix(39,75); groebnerMatrix(targetRow,48) = 0.0; groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_10100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,49) / groebnerMatrix(40,76); groebnerMatrix(targetRow,49) = 0.0; groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow36_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,52) / groebnerMatrix(36,72); groebnerMatrix(targetRow,52) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(36,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow37_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,56) / groebnerMatrix(37,73); groebnerMatrix(targetRow,56) = 0.0; groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(37,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_00100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,64) / groebnerMatrix(40,76); groebnerMatrix(targetRow,64) = 0.0; groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,67) / groebnerMatrix(40,76); groebnerMatrix(targetRow,67) = 0.0; groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,71) / groebnerMatrix(40,76); groebnerMatrix(targetRow,71) = 0.0; groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,76) / groebnerMatrix(40,76); groebnerMatrix(targetRow,76) = 0.0; groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_02000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,41) / groebnerMatrix(39,75); groebnerMatrix(targetRow,41) = 0.0; groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_02000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,42) / groebnerMatrix(40,76); groebnerMatrix(targetRow,42) = 0.0; groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow41_02000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,43) / groebnerMatrix(41,77); groebnerMatrix(targetRow,43) = 0.0; groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(41,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,50) / groebnerMatrix(38,74); groebnerMatrix(targetRow,50) = 0.0; groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,51) / groebnerMatrix(39,75); groebnerMatrix(targetRow,51) = 0.0; groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,52) / groebnerMatrix(40,76); groebnerMatrix(targetRow,52) = 0.0; groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow41_11000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,53) / groebnerMatrix(41,77); groebnerMatrix(targetRow,53) = 0.0; groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(41,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow37_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,57) / groebnerMatrix(37,73); groebnerMatrix(targetRow,57) = 0.0; groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(37,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow41_01000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,68) / groebnerMatrix(41,77); groebnerMatrix(targetRow,68) = 0.0; groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(41,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow41_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,72) / groebnerMatrix(41,77); groebnerMatrix(targetRow,72) = 0.0; groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(41,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow41_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,77) / groebnerMatrix(41,77); groebnerMatrix(targetRow,77) = 0.0; groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(41,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow38_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,54) / groebnerMatrix(38,74); groebnerMatrix(targetRow,54) = 0.0; groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(38,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow39_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,55) / groebnerMatrix(39,75); groebnerMatrix(targetRow,55) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(39,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow40_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,56) / groebnerMatrix(40,76); groebnerMatrix(targetRow,56) = 0.0; groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(40,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow41_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,57) / groebnerMatrix(41,77); groebnerMatrix(targetRow,57) = 0.0; groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(41,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow42_20000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,58) / groebnerMatrix(42,78); groebnerMatrix(targetRow,58) = 0.0; groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(42,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow42_10000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,73) / groebnerMatrix(42,78); groebnerMatrix(targetRow,73) = 0.0; groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(42,79); } void opengv::absolute_pose::modules::gpnp5::groebnerRow42_00000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,78) / groebnerMatrix(42,78); groebnerMatrix(targetRow,78) = 0.0; groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(42,79); } opengv/src/absolute_pose/modules/gpnp5/spolynomials.cpp0000664016516101651610000031340013344612246022401 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp5::sPolynomial6( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(6,60) = (groebnerMatrix(0,60)/(groebnerMatrix(0,59))-groebnerMatrix(1,60)/(groebnerMatrix(1,59))); groebnerMatrix(6,61) = (groebnerMatrix(0,61)/(groebnerMatrix(0,59))-groebnerMatrix(1,61)/(groebnerMatrix(1,59))); groebnerMatrix(6,62) = (groebnerMatrix(0,62)/(groebnerMatrix(0,59))-groebnerMatrix(1,62)/(groebnerMatrix(1,59))); groebnerMatrix(6,63) = (groebnerMatrix(0,63)/(groebnerMatrix(0,59))-groebnerMatrix(1,63)/(groebnerMatrix(1,59))); groebnerMatrix(6,64) = (groebnerMatrix(0,64)/(groebnerMatrix(0,59))-groebnerMatrix(1,64)/(groebnerMatrix(1,59))); groebnerMatrix(6,65) = (groebnerMatrix(0,65)/(groebnerMatrix(0,59))-groebnerMatrix(1,65)/(groebnerMatrix(1,59))); groebnerMatrix(6,66) = (groebnerMatrix(0,66)/(groebnerMatrix(0,59))-groebnerMatrix(1,66)/(groebnerMatrix(1,59))); groebnerMatrix(6,67) = (groebnerMatrix(0,67)/(groebnerMatrix(0,59))-groebnerMatrix(1,67)/(groebnerMatrix(1,59))); groebnerMatrix(6,68) = (groebnerMatrix(0,68)/(groebnerMatrix(0,59))-groebnerMatrix(1,68)/(groebnerMatrix(1,59))); groebnerMatrix(6,69) = (groebnerMatrix(0,69)/(groebnerMatrix(0,59))-groebnerMatrix(1,69)/(groebnerMatrix(1,59))); groebnerMatrix(6,70) = (groebnerMatrix(0,70)/(groebnerMatrix(0,59))-groebnerMatrix(1,70)/(groebnerMatrix(1,59))); groebnerMatrix(6,71) = (groebnerMatrix(0,71)/(groebnerMatrix(0,59))-groebnerMatrix(1,71)/(groebnerMatrix(1,59))); groebnerMatrix(6,72) = (groebnerMatrix(0,72)/(groebnerMatrix(0,59))-groebnerMatrix(1,72)/(groebnerMatrix(1,59))); groebnerMatrix(6,73) = (groebnerMatrix(0,73)/(groebnerMatrix(0,59))-groebnerMatrix(1,73)/(groebnerMatrix(1,59))); groebnerMatrix(6,74) = (groebnerMatrix(0,74)/(groebnerMatrix(0,59))-groebnerMatrix(1,74)/(groebnerMatrix(1,59))); groebnerMatrix(6,75) = (groebnerMatrix(0,75)/(groebnerMatrix(0,59))-groebnerMatrix(1,75)/(groebnerMatrix(1,59))); groebnerMatrix(6,76) = (groebnerMatrix(0,76)/(groebnerMatrix(0,59))-groebnerMatrix(1,76)/(groebnerMatrix(1,59))); groebnerMatrix(6,77) = (groebnerMatrix(0,77)/(groebnerMatrix(0,59))-groebnerMatrix(1,77)/(groebnerMatrix(1,59))); groebnerMatrix(6,78) = (groebnerMatrix(0,78)/(groebnerMatrix(0,59))-groebnerMatrix(1,78)/(groebnerMatrix(1,59))); groebnerMatrix(6,79) = (groebnerMatrix(0,79)/(groebnerMatrix(0,59))-groebnerMatrix(1,79)/(groebnerMatrix(1,59))); } void opengv::absolute_pose::modules::gpnp5::sPolynomial7( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(7,60) = (groebnerMatrix(1,60)/(groebnerMatrix(1,59))-groebnerMatrix(2,60)/(groebnerMatrix(2,59))); groebnerMatrix(7,61) = (groebnerMatrix(1,61)/(groebnerMatrix(1,59))-groebnerMatrix(2,61)/(groebnerMatrix(2,59))); groebnerMatrix(7,62) = (groebnerMatrix(1,62)/(groebnerMatrix(1,59))-groebnerMatrix(2,62)/(groebnerMatrix(2,59))); groebnerMatrix(7,63) = (groebnerMatrix(1,63)/(groebnerMatrix(1,59))-groebnerMatrix(2,63)/(groebnerMatrix(2,59))); groebnerMatrix(7,64) = (groebnerMatrix(1,64)/(groebnerMatrix(1,59))-groebnerMatrix(2,64)/(groebnerMatrix(2,59))); groebnerMatrix(7,65) = (groebnerMatrix(1,65)/(groebnerMatrix(1,59))-groebnerMatrix(2,65)/(groebnerMatrix(2,59))); groebnerMatrix(7,66) = (groebnerMatrix(1,66)/(groebnerMatrix(1,59))-groebnerMatrix(2,66)/(groebnerMatrix(2,59))); groebnerMatrix(7,67) = (groebnerMatrix(1,67)/(groebnerMatrix(1,59))-groebnerMatrix(2,67)/(groebnerMatrix(2,59))); groebnerMatrix(7,68) = (groebnerMatrix(1,68)/(groebnerMatrix(1,59))-groebnerMatrix(2,68)/(groebnerMatrix(2,59))); groebnerMatrix(7,69) = (groebnerMatrix(1,69)/(groebnerMatrix(1,59))-groebnerMatrix(2,69)/(groebnerMatrix(2,59))); groebnerMatrix(7,70) = (groebnerMatrix(1,70)/(groebnerMatrix(1,59))-groebnerMatrix(2,70)/(groebnerMatrix(2,59))); groebnerMatrix(7,71) = (groebnerMatrix(1,71)/(groebnerMatrix(1,59))-groebnerMatrix(2,71)/(groebnerMatrix(2,59))); groebnerMatrix(7,72) = (groebnerMatrix(1,72)/(groebnerMatrix(1,59))-groebnerMatrix(2,72)/(groebnerMatrix(2,59))); groebnerMatrix(7,73) = (groebnerMatrix(1,73)/(groebnerMatrix(1,59))-groebnerMatrix(2,73)/(groebnerMatrix(2,59))); groebnerMatrix(7,74) = (groebnerMatrix(1,74)/(groebnerMatrix(1,59))-groebnerMatrix(2,74)/(groebnerMatrix(2,59))); groebnerMatrix(7,75) = (groebnerMatrix(1,75)/(groebnerMatrix(1,59))-groebnerMatrix(2,75)/(groebnerMatrix(2,59))); groebnerMatrix(7,76) = (groebnerMatrix(1,76)/(groebnerMatrix(1,59))-groebnerMatrix(2,76)/(groebnerMatrix(2,59))); groebnerMatrix(7,77) = (groebnerMatrix(1,77)/(groebnerMatrix(1,59))-groebnerMatrix(2,77)/(groebnerMatrix(2,59))); groebnerMatrix(7,78) = (groebnerMatrix(1,78)/(groebnerMatrix(1,59))-groebnerMatrix(2,78)/(groebnerMatrix(2,59))); groebnerMatrix(7,79) = (groebnerMatrix(1,79)/(groebnerMatrix(1,59))-groebnerMatrix(2,79)/(groebnerMatrix(2,59))); } void opengv::absolute_pose::modules::gpnp5::sPolynomial8( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(8,60) = (groebnerMatrix(2,60)/(groebnerMatrix(2,59))-groebnerMatrix(3,60)/(groebnerMatrix(3,59))); groebnerMatrix(8,61) = (groebnerMatrix(2,61)/(groebnerMatrix(2,59))-groebnerMatrix(3,61)/(groebnerMatrix(3,59))); groebnerMatrix(8,62) = (groebnerMatrix(2,62)/(groebnerMatrix(2,59))-groebnerMatrix(3,62)/(groebnerMatrix(3,59))); groebnerMatrix(8,63) = (groebnerMatrix(2,63)/(groebnerMatrix(2,59))-groebnerMatrix(3,63)/(groebnerMatrix(3,59))); groebnerMatrix(8,64) = (groebnerMatrix(2,64)/(groebnerMatrix(2,59))-groebnerMatrix(3,64)/(groebnerMatrix(3,59))); groebnerMatrix(8,65) = (groebnerMatrix(2,65)/(groebnerMatrix(2,59))-groebnerMatrix(3,65)/(groebnerMatrix(3,59))); groebnerMatrix(8,66) = (groebnerMatrix(2,66)/(groebnerMatrix(2,59))-groebnerMatrix(3,66)/(groebnerMatrix(3,59))); groebnerMatrix(8,67) = (groebnerMatrix(2,67)/(groebnerMatrix(2,59))-groebnerMatrix(3,67)/(groebnerMatrix(3,59))); groebnerMatrix(8,68) = (groebnerMatrix(2,68)/(groebnerMatrix(2,59))-groebnerMatrix(3,68)/(groebnerMatrix(3,59))); groebnerMatrix(8,69) = (groebnerMatrix(2,69)/(groebnerMatrix(2,59))-groebnerMatrix(3,69)/(groebnerMatrix(3,59))); groebnerMatrix(8,70) = (groebnerMatrix(2,70)/(groebnerMatrix(2,59))-groebnerMatrix(3,70)/(groebnerMatrix(3,59))); groebnerMatrix(8,71) = (groebnerMatrix(2,71)/(groebnerMatrix(2,59))-groebnerMatrix(3,71)/(groebnerMatrix(3,59))); groebnerMatrix(8,72) = (groebnerMatrix(2,72)/(groebnerMatrix(2,59))-groebnerMatrix(3,72)/(groebnerMatrix(3,59))); groebnerMatrix(8,73) = (groebnerMatrix(2,73)/(groebnerMatrix(2,59))-groebnerMatrix(3,73)/(groebnerMatrix(3,59))); groebnerMatrix(8,74) = (groebnerMatrix(2,74)/(groebnerMatrix(2,59))-groebnerMatrix(3,74)/(groebnerMatrix(3,59))); groebnerMatrix(8,75) = (groebnerMatrix(2,75)/(groebnerMatrix(2,59))-groebnerMatrix(3,75)/(groebnerMatrix(3,59))); groebnerMatrix(8,76) = (groebnerMatrix(2,76)/(groebnerMatrix(2,59))-groebnerMatrix(3,76)/(groebnerMatrix(3,59))); groebnerMatrix(8,77) = (groebnerMatrix(2,77)/(groebnerMatrix(2,59))-groebnerMatrix(3,77)/(groebnerMatrix(3,59))); groebnerMatrix(8,78) = (groebnerMatrix(2,78)/(groebnerMatrix(2,59))-groebnerMatrix(3,78)/(groebnerMatrix(3,59))); groebnerMatrix(8,79) = (groebnerMatrix(2,79)/(groebnerMatrix(2,59))-groebnerMatrix(3,79)/(groebnerMatrix(3,59))); } void opengv::absolute_pose::modules::gpnp5::sPolynomial9( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(9,60) = (groebnerMatrix(3,60)/(groebnerMatrix(3,59))-groebnerMatrix(4,60)/(groebnerMatrix(4,59))); groebnerMatrix(9,61) = (groebnerMatrix(3,61)/(groebnerMatrix(3,59))-groebnerMatrix(4,61)/(groebnerMatrix(4,59))); groebnerMatrix(9,62) = (groebnerMatrix(3,62)/(groebnerMatrix(3,59))-groebnerMatrix(4,62)/(groebnerMatrix(4,59))); groebnerMatrix(9,63) = (groebnerMatrix(3,63)/(groebnerMatrix(3,59))-groebnerMatrix(4,63)/(groebnerMatrix(4,59))); groebnerMatrix(9,64) = (groebnerMatrix(3,64)/(groebnerMatrix(3,59))-groebnerMatrix(4,64)/(groebnerMatrix(4,59))); groebnerMatrix(9,65) = (groebnerMatrix(3,65)/(groebnerMatrix(3,59))-groebnerMatrix(4,65)/(groebnerMatrix(4,59))); groebnerMatrix(9,66) = (groebnerMatrix(3,66)/(groebnerMatrix(3,59))-groebnerMatrix(4,66)/(groebnerMatrix(4,59))); groebnerMatrix(9,67) = (groebnerMatrix(3,67)/(groebnerMatrix(3,59))-groebnerMatrix(4,67)/(groebnerMatrix(4,59))); groebnerMatrix(9,68) = (groebnerMatrix(3,68)/(groebnerMatrix(3,59))-groebnerMatrix(4,68)/(groebnerMatrix(4,59))); groebnerMatrix(9,69) = (groebnerMatrix(3,69)/(groebnerMatrix(3,59))-groebnerMatrix(4,69)/(groebnerMatrix(4,59))); groebnerMatrix(9,70) = (groebnerMatrix(3,70)/(groebnerMatrix(3,59))-groebnerMatrix(4,70)/(groebnerMatrix(4,59))); groebnerMatrix(9,71) = (groebnerMatrix(3,71)/(groebnerMatrix(3,59))-groebnerMatrix(4,71)/(groebnerMatrix(4,59))); groebnerMatrix(9,72) = (groebnerMatrix(3,72)/(groebnerMatrix(3,59))-groebnerMatrix(4,72)/(groebnerMatrix(4,59))); groebnerMatrix(9,73) = (groebnerMatrix(3,73)/(groebnerMatrix(3,59))-groebnerMatrix(4,73)/(groebnerMatrix(4,59))); groebnerMatrix(9,74) = (groebnerMatrix(3,74)/(groebnerMatrix(3,59))-groebnerMatrix(4,74)/(groebnerMatrix(4,59))); groebnerMatrix(9,75) = (groebnerMatrix(3,75)/(groebnerMatrix(3,59))-groebnerMatrix(4,75)/(groebnerMatrix(4,59))); groebnerMatrix(9,76) = (groebnerMatrix(3,76)/(groebnerMatrix(3,59))-groebnerMatrix(4,76)/(groebnerMatrix(4,59))); groebnerMatrix(9,77) = (groebnerMatrix(3,77)/(groebnerMatrix(3,59))-groebnerMatrix(4,77)/(groebnerMatrix(4,59))); groebnerMatrix(9,78) = (groebnerMatrix(3,78)/(groebnerMatrix(3,59))-groebnerMatrix(4,78)/(groebnerMatrix(4,59))); groebnerMatrix(9,79) = (groebnerMatrix(3,79)/(groebnerMatrix(3,59))-groebnerMatrix(4,79)/(groebnerMatrix(4,59))); } void opengv::absolute_pose::modules::gpnp5::sPolynomial10( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(10,60) = (groebnerMatrix(4,60)/(groebnerMatrix(4,59))-groebnerMatrix(5,60)/(groebnerMatrix(5,59))); groebnerMatrix(10,61) = (groebnerMatrix(4,61)/(groebnerMatrix(4,59))-groebnerMatrix(5,61)/(groebnerMatrix(5,59))); groebnerMatrix(10,62) = (groebnerMatrix(4,62)/(groebnerMatrix(4,59))-groebnerMatrix(5,62)/(groebnerMatrix(5,59))); groebnerMatrix(10,63) = (groebnerMatrix(4,63)/(groebnerMatrix(4,59))-groebnerMatrix(5,63)/(groebnerMatrix(5,59))); groebnerMatrix(10,64) = (groebnerMatrix(4,64)/(groebnerMatrix(4,59))-groebnerMatrix(5,64)/(groebnerMatrix(5,59))); groebnerMatrix(10,65) = (groebnerMatrix(4,65)/(groebnerMatrix(4,59))-groebnerMatrix(5,65)/(groebnerMatrix(5,59))); groebnerMatrix(10,66) = (groebnerMatrix(4,66)/(groebnerMatrix(4,59))-groebnerMatrix(5,66)/(groebnerMatrix(5,59))); groebnerMatrix(10,67) = (groebnerMatrix(4,67)/(groebnerMatrix(4,59))-groebnerMatrix(5,67)/(groebnerMatrix(5,59))); groebnerMatrix(10,68) = (groebnerMatrix(4,68)/(groebnerMatrix(4,59))-groebnerMatrix(5,68)/(groebnerMatrix(5,59))); groebnerMatrix(10,69) = (groebnerMatrix(4,69)/(groebnerMatrix(4,59))-groebnerMatrix(5,69)/(groebnerMatrix(5,59))); groebnerMatrix(10,70) = (groebnerMatrix(4,70)/(groebnerMatrix(4,59))-groebnerMatrix(5,70)/(groebnerMatrix(5,59))); groebnerMatrix(10,71) = (groebnerMatrix(4,71)/(groebnerMatrix(4,59))-groebnerMatrix(5,71)/(groebnerMatrix(5,59))); groebnerMatrix(10,72) = (groebnerMatrix(4,72)/(groebnerMatrix(4,59))-groebnerMatrix(5,72)/(groebnerMatrix(5,59))); groebnerMatrix(10,73) = (groebnerMatrix(4,73)/(groebnerMatrix(4,59))-groebnerMatrix(5,73)/(groebnerMatrix(5,59))); groebnerMatrix(10,74) = (groebnerMatrix(4,74)/(groebnerMatrix(4,59))-groebnerMatrix(5,74)/(groebnerMatrix(5,59))); groebnerMatrix(10,75) = (groebnerMatrix(4,75)/(groebnerMatrix(4,59))-groebnerMatrix(5,75)/(groebnerMatrix(5,59))); groebnerMatrix(10,76) = (groebnerMatrix(4,76)/(groebnerMatrix(4,59))-groebnerMatrix(5,76)/(groebnerMatrix(5,59))); groebnerMatrix(10,77) = (groebnerMatrix(4,77)/(groebnerMatrix(4,59))-groebnerMatrix(5,77)/(groebnerMatrix(5,59))); groebnerMatrix(10,78) = (groebnerMatrix(4,78)/(groebnerMatrix(4,59))-groebnerMatrix(5,78)/(groebnerMatrix(5,59))); groebnerMatrix(10,79) = (groebnerMatrix(4,79)/(groebnerMatrix(4,59))-groebnerMatrix(5,79)/(groebnerMatrix(5,59))); } void opengv::absolute_pose::modules::gpnp5::sPolynomial11( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(11,33) = groebnerMatrix(9,64)/(groebnerMatrix(9,63)); groebnerMatrix(11,35) = -groebnerMatrix(10,65)/(groebnerMatrix(10,64)); groebnerMatrix(11,36) = -groebnerMatrix(10,66)/(groebnerMatrix(10,64)); groebnerMatrix(11,37) = groebnerMatrix(9,65)/(groebnerMatrix(9,63)); groebnerMatrix(11,38) = (groebnerMatrix(9,66)/(groebnerMatrix(9,63))-groebnerMatrix(10,67)/(groebnerMatrix(10,64))); groebnerMatrix(11,39) = groebnerMatrix(9,67)/(groebnerMatrix(9,63)); groebnerMatrix(11,41) = -groebnerMatrix(10,68)/(groebnerMatrix(10,64)); groebnerMatrix(11,42) = groebnerMatrix(9,68)/(groebnerMatrix(9,63)); groebnerMatrix(11,45) = -groebnerMatrix(10,69)/(groebnerMatrix(10,64)); groebnerMatrix(11,46) = -groebnerMatrix(10,70)/(groebnerMatrix(10,64)); groebnerMatrix(11,47) = groebnerMatrix(9,69)/(groebnerMatrix(9,63)); groebnerMatrix(11,48) = (groebnerMatrix(9,70)/(groebnerMatrix(9,63))-groebnerMatrix(10,71)/(groebnerMatrix(10,64))); groebnerMatrix(11,49) = groebnerMatrix(9,71)/(groebnerMatrix(9,63)); groebnerMatrix(11,51) = -groebnerMatrix(10,72)/(groebnerMatrix(10,64)); groebnerMatrix(11,52) = groebnerMatrix(9,72)/(groebnerMatrix(9,63)); groebnerMatrix(11,55) = -groebnerMatrix(10,73)/(groebnerMatrix(10,64)); groebnerMatrix(11,56) = groebnerMatrix(9,73)/(groebnerMatrix(9,63)); groebnerMatrix(11,60) = -groebnerMatrix(10,74)/(groebnerMatrix(10,64)); groebnerMatrix(11,61) = -groebnerMatrix(10,75)/(groebnerMatrix(10,64)); groebnerMatrix(11,62) = groebnerMatrix(9,74)/(groebnerMatrix(9,63)); groebnerMatrix(11,63) = (groebnerMatrix(9,75)/(groebnerMatrix(9,63))-groebnerMatrix(10,76)/(groebnerMatrix(10,64))); groebnerMatrix(11,64) = groebnerMatrix(9,76)/(groebnerMatrix(9,63)); groebnerMatrix(11,66) = -groebnerMatrix(10,77)/(groebnerMatrix(10,64)); groebnerMatrix(11,67) = groebnerMatrix(9,77)/(groebnerMatrix(9,63)); groebnerMatrix(11,70) = -groebnerMatrix(10,78)/(groebnerMatrix(10,64)); groebnerMatrix(11,71) = groebnerMatrix(9,78)/(groebnerMatrix(9,63)); groebnerMatrix(11,75) = -groebnerMatrix(10,79)/(groebnerMatrix(10,64)); groebnerMatrix(11,76) = groebnerMatrix(9,79)/(groebnerMatrix(9,63)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial12( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(12,32) = groebnerMatrix(8,63)/(groebnerMatrix(8,62)); groebnerMatrix(12,33) = groebnerMatrix(8,64)/(groebnerMatrix(8,62)); groebnerMatrix(12,34) = -groebnerMatrix(10,65)/(groebnerMatrix(10,64)); groebnerMatrix(12,35) = -groebnerMatrix(10,66)/(groebnerMatrix(10,64)); groebnerMatrix(12,37) = (groebnerMatrix(8,65)/(groebnerMatrix(8,62))-groebnerMatrix(10,67)/(groebnerMatrix(10,64))); groebnerMatrix(12,38) = groebnerMatrix(8,66)/(groebnerMatrix(8,62)); groebnerMatrix(12,39) = groebnerMatrix(8,67)/(groebnerMatrix(8,62)); groebnerMatrix(12,40) = -groebnerMatrix(10,68)/(groebnerMatrix(10,64)); groebnerMatrix(12,42) = groebnerMatrix(8,68)/(groebnerMatrix(8,62)); groebnerMatrix(12,44) = -groebnerMatrix(10,69)/(groebnerMatrix(10,64)); groebnerMatrix(12,45) = -groebnerMatrix(10,70)/(groebnerMatrix(10,64)); groebnerMatrix(12,47) = (groebnerMatrix(8,69)/(groebnerMatrix(8,62))-groebnerMatrix(10,71)/(groebnerMatrix(10,64))); groebnerMatrix(12,48) = groebnerMatrix(8,70)/(groebnerMatrix(8,62)); groebnerMatrix(12,49) = groebnerMatrix(8,71)/(groebnerMatrix(8,62)); groebnerMatrix(12,50) = -groebnerMatrix(10,72)/(groebnerMatrix(10,64)); groebnerMatrix(12,52) = groebnerMatrix(8,72)/(groebnerMatrix(8,62)); groebnerMatrix(12,54) = -groebnerMatrix(10,73)/(groebnerMatrix(10,64)); groebnerMatrix(12,56) = groebnerMatrix(8,73)/(groebnerMatrix(8,62)); groebnerMatrix(12,59) = -groebnerMatrix(10,74)/(groebnerMatrix(10,64)); groebnerMatrix(12,60) = -groebnerMatrix(10,75)/(groebnerMatrix(10,64)); groebnerMatrix(12,62) = (groebnerMatrix(8,74)/(groebnerMatrix(8,62))-groebnerMatrix(10,76)/(groebnerMatrix(10,64))); groebnerMatrix(12,63) = groebnerMatrix(8,75)/(groebnerMatrix(8,62)); groebnerMatrix(12,64) = groebnerMatrix(8,76)/(groebnerMatrix(8,62)); groebnerMatrix(12,65) = -groebnerMatrix(10,77)/(groebnerMatrix(10,64)); groebnerMatrix(12,67) = groebnerMatrix(8,77)/(groebnerMatrix(8,62)); groebnerMatrix(12,69) = -groebnerMatrix(10,78)/(groebnerMatrix(10,64)); groebnerMatrix(12,71) = groebnerMatrix(8,78)/(groebnerMatrix(8,62)); groebnerMatrix(12,74) = -groebnerMatrix(10,79)/(groebnerMatrix(10,64)); groebnerMatrix(12,76) = groebnerMatrix(8,79)/(groebnerMatrix(8,62)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial13( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(13,31) = groebnerMatrix(7,62)/(groebnerMatrix(7,61)); groebnerMatrix(13,32) = (groebnerMatrix(7,63)/(groebnerMatrix(7,61))-groebnerMatrix(9,64)/(groebnerMatrix(9,63))); groebnerMatrix(13,33) = groebnerMatrix(7,64)/(groebnerMatrix(7,61)); groebnerMatrix(13,35) = -groebnerMatrix(9,65)/(groebnerMatrix(9,63)); groebnerMatrix(13,36) = -groebnerMatrix(9,66)/(groebnerMatrix(9,63)); groebnerMatrix(13,37) = groebnerMatrix(7,65)/(groebnerMatrix(7,61)); groebnerMatrix(13,38) = (groebnerMatrix(7,66)/(groebnerMatrix(7,61))-groebnerMatrix(9,67)/(groebnerMatrix(9,63))); groebnerMatrix(13,39) = groebnerMatrix(7,67)/(groebnerMatrix(7,61)); groebnerMatrix(13,41) = -groebnerMatrix(9,68)/(groebnerMatrix(9,63)); groebnerMatrix(13,42) = groebnerMatrix(7,68)/(groebnerMatrix(7,61)); groebnerMatrix(13,45) = -groebnerMatrix(9,69)/(groebnerMatrix(9,63)); groebnerMatrix(13,46) = -groebnerMatrix(9,70)/(groebnerMatrix(9,63)); groebnerMatrix(13,47) = groebnerMatrix(7,69)/(groebnerMatrix(7,61)); groebnerMatrix(13,48) = (groebnerMatrix(7,70)/(groebnerMatrix(7,61))-groebnerMatrix(9,71)/(groebnerMatrix(9,63))); groebnerMatrix(13,49) = groebnerMatrix(7,71)/(groebnerMatrix(7,61)); groebnerMatrix(13,51) = -groebnerMatrix(9,72)/(groebnerMatrix(9,63)); groebnerMatrix(13,52) = groebnerMatrix(7,72)/(groebnerMatrix(7,61)); groebnerMatrix(13,55) = -groebnerMatrix(9,73)/(groebnerMatrix(9,63)); groebnerMatrix(13,56) = groebnerMatrix(7,73)/(groebnerMatrix(7,61)); groebnerMatrix(13,60) = -groebnerMatrix(9,74)/(groebnerMatrix(9,63)); groebnerMatrix(13,61) = -groebnerMatrix(9,75)/(groebnerMatrix(9,63)); groebnerMatrix(13,62) = groebnerMatrix(7,74)/(groebnerMatrix(7,61)); groebnerMatrix(13,63) = (groebnerMatrix(7,75)/(groebnerMatrix(7,61))-groebnerMatrix(9,76)/(groebnerMatrix(9,63))); groebnerMatrix(13,64) = groebnerMatrix(7,76)/(groebnerMatrix(7,61)); groebnerMatrix(13,66) = -groebnerMatrix(9,77)/(groebnerMatrix(9,63)); groebnerMatrix(13,67) = groebnerMatrix(7,77)/(groebnerMatrix(7,61)); groebnerMatrix(13,70) = -groebnerMatrix(9,78)/(groebnerMatrix(9,63)); groebnerMatrix(13,71) = groebnerMatrix(7,78)/(groebnerMatrix(7,61)); groebnerMatrix(13,75) = -groebnerMatrix(9,79)/(groebnerMatrix(9,63)); groebnerMatrix(13,76) = groebnerMatrix(7,79)/(groebnerMatrix(7,61)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial14( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(14,30) = (groebnerMatrix(6,61)/(groebnerMatrix(6,60))-groebnerMatrix(8,63)/(groebnerMatrix(8,62))); groebnerMatrix(14,31) = groebnerMatrix(6,62)/(groebnerMatrix(6,60)); groebnerMatrix(14,32) = (groebnerMatrix(6,63)/(groebnerMatrix(6,60))-groebnerMatrix(8,64)/(groebnerMatrix(8,62))); groebnerMatrix(14,33) = groebnerMatrix(6,64)/(groebnerMatrix(6,60)); groebnerMatrix(14,35) = -groebnerMatrix(8,65)/(groebnerMatrix(8,62)); groebnerMatrix(14,36) = -groebnerMatrix(8,66)/(groebnerMatrix(8,62)); groebnerMatrix(14,37) = groebnerMatrix(6,65)/(groebnerMatrix(6,60)); groebnerMatrix(14,38) = (groebnerMatrix(6,66)/(groebnerMatrix(6,60))-groebnerMatrix(8,67)/(groebnerMatrix(8,62))); groebnerMatrix(14,39) = groebnerMatrix(6,67)/(groebnerMatrix(6,60)); groebnerMatrix(14,41) = -groebnerMatrix(8,68)/(groebnerMatrix(8,62)); groebnerMatrix(14,42) = groebnerMatrix(6,68)/(groebnerMatrix(6,60)); groebnerMatrix(14,45) = -groebnerMatrix(8,69)/(groebnerMatrix(8,62)); groebnerMatrix(14,46) = -groebnerMatrix(8,70)/(groebnerMatrix(8,62)); groebnerMatrix(14,47) = groebnerMatrix(6,69)/(groebnerMatrix(6,60)); groebnerMatrix(14,48) = (groebnerMatrix(6,70)/(groebnerMatrix(6,60))-groebnerMatrix(8,71)/(groebnerMatrix(8,62))); groebnerMatrix(14,49) = groebnerMatrix(6,71)/(groebnerMatrix(6,60)); groebnerMatrix(14,51) = -groebnerMatrix(8,72)/(groebnerMatrix(8,62)); groebnerMatrix(14,52) = groebnerMatrix(6,72)/(groebnerMatrix(6,60)); groebnerMatrix(14,55) = -groebnerMatrix(8,73)/(groebnerMatrix(8,62)); groebnerMatrix(14,56) = groebnerMatrix(6,73)/(groebnerMatrix(6,60)); groebnerMatrix(14,60) = -groebnerMatrix(8,74)/(groebnerMatrix(8,62)); groebnerMatrix(14,61) = -groebnerMatrix(8,75)/(groebnerMatrix(8,62)); groebnerMatrix(14,62) = groebnerMatrix(6,74)/(groebnerMatrix(6,60)); groebnerMatrix(14,63) = (groebnerMatrix(6,75)/(groebnerMatrix(6,60))-groebnerMatrix(8,76)/(groebnerMatrix(8,62))); groebnerMatrix(14,64) = groebnerMatrix(6,76)/(groebnerMatrix(6,60)); groebnerMatrix(14,66) = -groebnerMatrix(8,77)/(groebnerMatrix(8,62)); groebnerMatrix(14,67) = groebnerMatrix(6,77)/(groebnerMatrix(6,60)); groebnerMatrix(14,70) = -groebnerMatrix(8,78)/(groebnerMatrix(8,62)); groebnerMatrix(14,71) = groebnerMatrix(6,78)/(groebnerMatrix(6,60)); groebnerMatrix(14,75) = -groebnerMatrix(8,79)/(groebnerMatrix(8,62)); groebnerMatrix(14,76) = groebnerMatrix(6,79)/(groebnerMatrix(6,60)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial15( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(15,30) = groebnerMatrix(6,61)/(groebnerMatrix(6,60)); groebnerMatrix(15,31) = (groebnerMatrix(6,62)/(groebnerMatrix(6,60))-groebnerMatrix(9,64)/(groebnerMatrix(9,63))); groebnerMatrix(15,32) = groebnerMatrix(6,63)/(groebnerMatrix(6,60)); groebnerMatrix(15,33) = groebnerMatrix(6,64)/(groebnerMatrix(6,60)); groebnerMatrix(15,34) = -groebnerMatrix(9,65)/(groebnerMatrix(9,63)); groebnerMatrix(15,35) = -groebnerMatrix(9,66)/(groebnerMatrix(9,63)); groebnerMatrix(15,37) = (groebnerMatrix(6,65)/(groebnerMatrix(6,60))-groebnerMatrix(9,67)/(groebnerMatrix(9,63))); groebnerMatrix(15,38) = groebnerMatrix(6,66)/(groebnerMatrix(6,60)); groebnerMatrix(15,39) = groebnerMatrix(6,67)/(groebnerMatrix(6,60)); groebnerMatrix(15,40) = -groebnerMatrix(9,68)/(groebnerMatrix(9,63)); groebnerMatrix(15,42) = groebnerMatrix(6,68)/(groebnerMatrix(6,60)); groebnerMatrix(15,44) = -groebnerMatrix(9,69)/(groebnerMatrix(9,63)); groebnerMatrix(15,45) = -groebnerMatrix(9,70)/(groebnerMatrix(9,63)); groebnerMatrix(15,47) = (groebnerMatrix(6,69)/(groebnerMatrix(6,60))-groebnerMatrix(9,71)/(groebnerMatrix(9,63))); groebnerMatrix(15,48) = groebnerMatrix(6,70)/(groebnerMatrix(6,60)); groebnerMatrix(15,49) = groebnerMatrix(6,71)/(groebnerMatrix(6,60)); groebnerMatrix(15,50) = -groebnerMatrix(9,72)/(groebnerMatrix(9,63)); groebnerMatrix(15,52) = groebnerMatrix(6,72)/(groebnerMatrix(6,60)); groebnerMatrix(15,54) = -groebnerMatrix(9,73)/(groebnerMatrix(9,63)); groebnerMatrix(15,56) = groebnerMatrix(6,73)/(groebnerMatrix(6,60)); groebnerMatrix(15,59) = -groebnerMatrix(9,74)/(groebnerMatrix(9,63)); groebnerMatrix(15,60) = -groebnerMatrix(9,75)/(groebnerMatrix(9,63)); groebnerMatrix(15,62) = (groebnerMatrix(6,74)/(groebnerMatrix(6,60))-groebnerMatrix(9,76)/(groebnerMatrix(9,63))); groebnerMatrix(15,63) = groebnerMatrix(6,75)/(groebnerMatrix(6,60)); groebnerMatrix(15,64) = groebnerMatrix(6,76)/(groebnerMatrix(6,60)); groebnerMatrix(15,65) = -groebnerMatrix(9,77)/(groebnerMatrix(9,63)); groebnerMatrix(15,67) = groebnerMatrix(6,77)/(groebnerMatrix(6,60)); groebnerMatrix(15,69) = -groebnerMatrix(9,78)/(groebnerMatrix(9,63)); groebnerMatrix(15,71) = groebnerMatrix(6,78)/(groebnerMatrix(6,60)); groebnerMatrix(15,74) = -groebnerMatrix(9,79)/(groebnerMatrix(9,63)); groebnerMatrix(15,76) = groebnerMatrix(6,79)/(groebnerMatrix(6,60)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial16( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(16,29) = (groebnerMatrix(5,60)/(groebnerMatrix(5,59))-groebnerMatrix(8,63)/(groebnerMatrix(8,62))); groebnerMatrix(16,30) = groebnerMatrix(5,61)/(groebnerMatrix(5,59)); groebnerMatrix(16,31) = (groebnerMatrix(5,62)/(groebnerMatrix(5,59))-groebnerMatrix(8,64)/(groebnerMatrix(8,62))); groebnerMatrix(16,32) = groebnerMatrix(5,63)/(groebnerMatrix(5,59)); groebnerMatrix(16,33) = groebnerMatrix(5,64)/(groebnerMatrix(5,59)); groebnerMatrix(16,34) = -groebnerMatrix(8,65)/(groebnerMatrix(8,62)); groebnerMatrix(16,35) = -groebnerMatrix(8,66)/(groebnerMatrix(8,62)); groebnerMatrix(16,37) = (groebnerMatrix(5,65)/(groebnerMatrix(5,59))-groebnerMatrix(8,67)/(groebnerMatrix(8,62))); groebnerMatrix(16,38) = groebnerMatrix(5,66)/(groebnerMatrix(5,59)); groebnerMatrix(16,39) = groebnerMatrix(5,67)/(groebnerMatrix(5,59)); groebnerMatrix(16,40) = -groebnerMatrix(8,68)/(groebnerMatrix(8,62)); groebnerMatrix(16,42) = groebnerMatrix(5,68)/(groebnerMatrix(5,59)); groebnerMatrix(16,44) = -groebnerMatrix(8,69)/(groebnerMatrix(8,62)); groebnerMatrix(16,45) = -groebnerMatrix(8,70)/(groebnerMatrix(8,62)); groebnerMatrix(16,47) = (groebnerMatrix(5,69)/(groebnerMatrix(5,59))-groebnerMatrix(8,71)/(groebnerMatrix(8,62))); groebnerMatrix(16,48) = groebnerMatrix(5,70)/(groebnerMatrix(5,59)); groebnerMatrix(16,49) = groebnerMatrix(5,71)/(groebnerMatrix(5,59)); groebnerMatrix(16,50) = -groebnerMatrix(8,72)/(groebnerMatrix(8,62)); groebnerMatrix(16,52) = groebnerMatrix(5,72)/(groebnerMatrix(5,59)); groebnerMatrix(16,54) = -groebnerMatrix(8,73)/(groebnerMatrix(8,62)); groebnerMatrix(16,56) = groebnerMatrix(5,73)/(groebnerMatrix(5,59)); groebnerMatrix(16,59) = -groebnerMatrix(8,74)/(groebnerMatrix(8,62)); groebnerMatrix(16,60) = -groebnerMatrix(8,75)/(groebnerMatrix(8,62)); groebnerMatrix(16,62) = (groebnerMatrix(5,74)/(groebnerMatrix(5,59))-groebnerMatrix(8,76)/(groebnerMatrix(8,62))); groebnerMatrix(16,63) = groebnerMatrix(5,75)/(groebnerMatrix(5,59)); groebnerMatrix(16,64) = groebnerMatrix(5,76)/(groebnerMatrix(5,59)); groebnerMatrix(16,65) = -groebnerMatrix(8,77)/(groebnerMatrix(8,62)); groebnerMatrix(16,67) = groebnerMatrix(5,77)/(groebnerMatrix(5,59)); groebnerMatrix(16,69) = -groebnerMatrix(8,78)/(groebnerMatrix(8,62)); groebnerMatrix(16,71) = groebnerMatrix(5,78)/(groebnerMatrix(5,59)); groebnerMatrix(16,74) = -groebnerMatrix(8,79)/(groebnerMatrix(8,62)); groebnerMatrix(16,76) = groebnerMatrix(5,79)/(groebnerMatrix(5,59)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial17( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(17,27) = groebnerMatrix(6,61)/(groebnerMatrix(6,60)); groebnerMatrix(17,28) = -groebnerMatrix(7,62)/(groebnerMatrix(7,61)); groebnerMatrix(17,29) = (groebnerMatrix(6,62)/(groebnerMatrix(6,60))-groebnerMatrix(7,63)/(groebnerMatrix(7,61))); groebnerMatrix(17,30) = groebnerMatrix(6,63)/(groebnerMatrix(6,60)); groebnerMatrix(17,31) = -groebnerMatrix(7,64)/(groebnerMatrix(7,61)); groebnerMatrix(17,32) = groebnerMatrix(6,64)/(groebnerMatrix(6,60)); groebnerMatrix(17,34) = -groebnerMatrix(7,65)/(groebnerMatrix(7,61)); groebnerMatrix(17,35) = (groebnerMatrix(6,65)/(groebnerMatrix(6,60))-groebnerMatrix(7,66)/(groebnerMatrix(7,61))); groebnerMatrix(17,36) = groebnerMatrix(6,66)/(groebnerMatrix(6,60)); groebnerMatrix(17,37) = -groebnerMatrix(7,67)/(groebnerMatrix(7,61)); groebnerMatrix(17,38) = groebnerMatrix(6,67)/(groebnerMatrix(6,60)); groebnerMatrix(17,40) = -groebnerMatrix(7,68)/(groebnerMatrix(7,61)); groebnerMatrix(17,41) = groebnerMatrix(6,68)/(groebnerMatrix(6,60)); groebnerMatrix(17,44) = -groebnerMatrix(7,69)/(groebnerMatrix(7,61)); groebnerMatrix(17,45) = (groebnerMatrix(6,69)/(groebnerMatrix(6,60))-groebnerMatrix(7,70)/(groebnerMatrix(7,61))); groebnerMatrix(17,46) = groebnerMatrix(6,70)/(groebnerMatrix(6,60)); groebnerMatrix(17,47) = -groebnerMatrix(7,71)/(groebnerMatrix(7,61)); groebnerMatrix(17,48) = groebnerMatrix(6,71)/(groebnerMatrix(6,60)); groebnerMatrix(17,50) = -groebnerMatrix(7,72)/(groebnerMatrix(7,61)); groebnerMatrix(17,51) = groebnerMatrix(6,72)/(groebnerMatrix(6,60)); groebnerMatrix(17,54) = -groebnerMatrix(7,73)/(groebnerMatrix(7,61)); groebnerMatrix(17,55) = groebnerMatrix(6,73)/(groebnerMatrix(6,60)); groebnerMatrix(17,59) = -groebnerMatrix(7,74)/(groebnerMatrix(7,61)); groebnerMatrix(17,60) = (groebnerMatrix(6,74)/(groebnerMatrix(6,60))-groebnerMatrix(7,75)/(groebnerMatrix(7,61))); groebnerMatrix(17,61) = groebnerMatrix(6,75)/(groebnerMatrix(6,60)); groebnerMatrix(17,62) = -groebnerMatrix(7,76)/(groebnerMatrix(7,61)); groebnerMatrix(17,63) = groebnerMatrix(6,76)/(groebnerMatrix(6,60)); groebnerMatrix(17,65) = -groebnerMatrix(7,77)/(groebnerMatrix(7,61)); groebnerMatrix(17,66) = groebnerMatrix(6,77)/(groebnerMatrix(6,60)); groebnerMatrix(17,69) = -groebnerMatrix(7,78)/(groebnerMatrix(7,61)); groebnerMatrix(17,70) = groebnerMatrix(6,78)/(groebnerMatrix(6,60)); groebnerMatrix(17,74) = -groebnerMatrix(7,79)/(groebnerMatrix(7,61)); groebnerMatrix(17,75) = groebnerMatrix(6,79)/(groebnerMatrix(6,60)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial18( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(18,26) = (groebnerMatrix(5,60)/(groebnerMatrix(5,59))-groebnerMatrix(6,61)/(groebnerMatrix(6,60))); groebnerMatrix(18,27) = groebnerMatrix(5,61)/(groebnerMatrix(5,59)); groebnerMatrix(18,28) = -groebnerMatrix(6,62)/(groebnerMatrix(6,60)); groebnerMatrix(18,29) = (groebnerMatrix(5,62)/(groebnerMatrix(5,59))-groebnerMatrix(6,63)/(groebnerMatrix(6,60))); groebnerMatrix(18,30) = groebnerMatrix(5,63)/(groebnerMatrix(5,59)); groebnerMatrix(18,31) = -groebnerMatrix(6,64)/(groebnerMatrix(6,60)); groebnerMatrix(18,32) = groebnerMatrix(5,64)/(groebnerMatrix(5,59)); groebnerMatrix(18,34) = -groebnerMatrix(6,65)/(groebnerMatrix(6,60)); groebnerMatrix(18,35) = (groebnerMatrix(5,65)/(groebnerMatrix(5,59))-groebnerMatrix(6,66)/(groebnerMatrix(6,60))); groebnerMatrix(18,36) = groebnerMatrix(5,66)/(groebnerMatrix(5,59)); groebnerMatrix(18,37) = -groebnerMatrix(6,67)/(groebnerMatrix(6,60)); groebnerMatrix(18,38) = groebnerMatrix(5,67)/(groebnerMatrix(5,59)); groebnerMatrix(18,40) = -groebnerMatrix(6,68)/(groebnerMatrix(6,60)); groebnerMatrix(18,41) = groebnerMatrix(5,68)/(groebnerMatrix(5,59)); groebnerMatrix(18,44) = -groebnerMatrix(6,69)/(groebnerMatrix(6,60)); groebnerMatrix(18,45) = (groebnerMatrix(5,69)/(groebnerMatrix(5,59))-groebnerMatrix(6,70)/(groebnerMatrix(6,60))); groebnerMatrix(18,46) = groebnerMatrix(5,70)/(groebnerMatrix(5,59)); groebnerMatrix(18,47) = -groebnerMatrix(6,71)/(groebnerMatrix(6,60)); groebnerMatrix(18,48) = groebnerMatrix(5,71)/(groebnerMatrix(5,59)); groebnerMatrix(18,50) = -groebnerMatrix(6,72)/(groebnerMatrix(6,60)); groebnerMatrix(18,51) = groebnerMatrix(5,72)/(groebnerMatrix(5,59)); groebnerMatrix(18,54) = -groebnerMatrix(6,73)/(groebnerMatrix(6,60)); groebnerMatrix(18,55) = groebnerMatrix(5,73)/(groebnerMatrix(5,59)); groebnerMatrix(18,59) = -groebnerMatrix(6,74)/(groebnerMatrix(6,60)); groebnerMatrix(18,60) = (groebnerMatrix(5,74)/(groebnerMatrix(5,59))-groebnerMatrix(6,75)/(groebnerMatrix(6,60))); groebnerMatrix(18,61) = groebnerMatrix(5,75)/(groebnerMatrix(5,59)); groebnerMatrix(18,62) = -groebnerMatrix(6,76)/(groebnerMatrix(6,60)); groebnerMatrix(18,63) = groebnerMatrix(5,76)/(groebnerMatrix(5,59)); groebnerMatrix(18,65) = -groebnerMatrix(6,77)/(groebnerMatrix(6,60)); groebnerMatrix(18,66) = groebnerMatrix(5,77)/(groebnerMatrix(5,59)); groebnerMatrix(18,69) = -groebnerMatrix(6,78)/(groebnerMatrix(6,60)); groebnerMatrix(18,70) = groebnerMatrix(5,78)/(groebnerMatrix(5,59)); groebnerMatrix(18,74) = -groebnerMatrix(6,79)/(groebnerMatrix(6,60)); groebnerMatrix(18,75) = groebnerMatrix(5,79)/(groebnerMatrix(5,59)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial19( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(19,17) = (groebnerMatrix(14,50)/(groebnerMatrix(14,43))-groebnerMatrix(18,54)/(groebnerMatrix(18,53))); groebnerMatrix(19,18) = (groebnerMatrix(14,51)/(groebnerMatrix(14,43))-groebnerMatrix(18,55)/(groebnerMatrix(18,53))); groebnerMatrix(19,19) = (groebnerMatrix(14,52)/(groebnerMatrix(14,43))-groebnerMatrix(18,56)/(groebnerMatrix(18,53))); groebnerMatrix(19,20) = (groebnerMatrix(14,53)/(groebnerMatrix(14,43))-groebnerMatrix(18,57)/(groebnerMatrix(18,53))); groebnerMatrix(19,21) = groebnerMatrix(14,54)/(groebnerMatrix(14,43)); groebnerMatrix(19,22) = groebnerMatrix(14,55)/(groebnerMatrix(14,43)); groebnerMatrix(19,23) = groebnerMatrix(14,56)/(groebnerMatrix(14,43)); groebnerMatrix(19,24) = (groebnerMatrix(14,57)/(groebnerMatrix(14,43))-groebnerMatrix(18,58)/(groebnerMatrix(18,53))); groebnerMatrix(19,25) = groebnerMatrix(14,58)/(groebnerMatrix(14,43)); groebnerMatrix(19,40) = -groebnerMatrix(18,65)/(groebnerMatrix(18,53)); groebnerMatrix(19,41) = -groebnerMatrix(18,66)/(groebnerMatrix(18,53)); groebnerMatrix(19,42) = -groebnerMatrix(18,67)/(groebnerMatrix(18,53)); groebnerMatrix(19,43) = -groebnerMatrix(18,68)/(groebnerMatrix(18,53)); groebnerMatrix(19,50) = (groebnerMatrix(14,65)/(groebnerMatrix(14,43))-groebnerMatrix(18,69)/(groebnerMatrix(18,53))); groebnerMatrix(19,51) = (groebnerMatrix(14,66)/(groebnerMatrix(14,43))-groebnerMatrix(18,70)/(groebnerMatrix(18,53))); groebnerMatrix(19,52) = (groebnerMatrix(14,67)/(groebnerMatrix(14,43))-groebnerMatrix(18,71)/(groebnerMatrix(18,53))); groebnerMatrix(19,53) = (groebnerMatrix(14,68)/(groebnerMatrix(14,43))-groebnerMatrix(18,72)/(groebnerMatrix(18,53))); groebnerMatrix(19,54) = groebnerMatrix(14,69)/(groebnerMatrix(14,43)); groebnerMatrix(19,55) = groebnerMatrix(14,70)/(groebnerMatrix(14,43)); groebnerMatrix(19,56) = groebnerMatrix(14,71)/(groebnerMatrix(14,43)); groebnerMatrix(19,57) = (groebnerMatrix(14,72)/(groebnerMatrix(14,43))-groebnerMatrix(18,73)/(groebnerMatrix(18,53))); groebnerMatrix(19,58) = groebnerMatrix(14,73)/(groebnerMatrix(14,43)); groebnerMatrix(19,65) = -groebnerMatrix(18,74)/(groebnerMatrix(18,53)); groebnerMatrix(19,66) = -groebnerMatrix(18,75)/(groebnerMatrix(18,53)); groebnerMatrix(19,67) = -groebnerMatrix(18,76)/(groebnerMatrix(18,53)); groebnerMatrix(19,68) = -groebnerMatrix(18,77)/(groebnerMatrix(18,53)); groebnerMatrix(19,69) = groebnerMatrix(14,74)/(groebnerMatrix(14,43)); groebnerMatrix(19,70) = groebnerMatrix(14,75)/(groebnerMatrix(14,43)); groebnerMatrix(19,71) = groebnerMatrix(14,76)/(groebnerMatrix(14,43)); groebnerMatrix(19,72) = (groebnerMatrix(14,77)/(groebnerMatrix(14,43))-groebnerMatrix(18,78)/(groebnerMatrix(18,53))); groebnerMatrix(19,73) = groebnerMatrix(14,78)/(groebnerMatrix(14,43)); groebnerMatrix(19,77) = -groebnerMatrix(18,79)/(groebnerMatrix(18,53)); groebnerMatrix(19,78) = groebnerMatrix(14,79)/(groebnerMatrix(14,43)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial20( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(20,10) = (groebnerMatrix(13,43)/(groebnerMatrix(13,42))-groebnerMatrix(17,53)/(groebnerMatrix(17,52))); groebnerMatrix(20,17) = (groebnerMatrix(13,50)/(groebnerMatrix(13,42))-groebnerMatrix(17,54)/(groebnerMatrix(17,52))); groebnerMatrix(20,18) = (groebnerMatrix(13,51)/(groebnerMatrix(13,42))-groebnerMatrix(17,55)/(groebnerMatrix(17,52))); groebnerMatrix(20,19) = (groebnerMatrix(13,52)/(groebnerMatrix(13,42))-groebnerMatrix(17,56)/(groebnerMatrix(17,52))); groebnerMatrix(20,20) = (groebnerMatrix(13,53)/(groebnerMatrix(13,42))-groebnerMatrix(17,57)/(groebnerMatrix(17,52))); groebnerMatrix(20,21) = groebnerMatrix(13,54)/(groebnerMatrix(13,42)); groebnerMatrix(20,22) = groebnerMatrix(13,55)/(groebnerMatrix(13,42)); groebnerMatrix(20,23) = groebnerMatrix(13,56)/(groebnerMatrix(13,42)); groebnerMatrix(20,24) = (groebnerMatrix(13,57)/(groebnerMatrix(13,42))-groebnerMatrix(17,58)/(groebnerMatrix(17,52))); groebnerMatrix(20,25) = groebnerMatrix(13,58)/(groebnerMatrix(13,42)); groebnerMatrix(20,40) = -groebnerMatrix(17,65)/(groebnerMatrix(17,52)); groebnerMatrix(20,41) = -groebnerMatrix(17,66)/(groebnerMatrix(17,52)); groebnerMatrix(20,42) = -groebnerMatrix(17,67)/(groebnerMatrix(17,52)); groebnerMatrix(20,43) = -groebnerMatrix(17,68)/(groebnerMatrix(17,52)); groebnerMatrix(20,50) = (groebnerMatrix(13,65)/(groebnerMatrix(13,42))-groebnerMatrix(17,69)/(groebnerMatrix(17,52))); groebnerMatrix(20,51) = (groebnerMatrix(13,66)/(groebnerMatrix(13,42))-groebnerMatrix(17,70)/(groebnerMatrix(17,52))); groebnerMatrix(20,52) = (groebnerMatrix(13,67)/(groebnerMatrix(13,42))-groebnerMatrix(17,71)/(groebnerMatrix(17,52))); groebnerMatrix(20,53) = (groebnerMatrix(13,68)/(groebnerMatrix(13,42))-groebnerMatrix(17,72)/(groebnerMatrix(17,52))); groebnerMatrix(20,54) = groebnerMatrix(13,69)/(groebnerMatrix(13,42)); groebnerMatrix(20,55) = groebnerMatrix(13,70)/(groebnerMatrix(13,42)); groebnerMatrix(20,56) = groebnerMatrix(13,71)/(groebnerMatrix(13,42)); groebnerMatrix(20,57) = (groebnerMatrix(13,72)/(groebnerMatrix(13,42))-groebnerMatrix(17,73)/(groebnerMatrix(17,52))); groebnerMatrix(20,58) = groebnerMatrix(13,73)/(groebnerMatrix(13,42)); groebnerMatrix(20,65) = -groebnerMatrix(17,74)/(groebnerMatrix(17,52)); groebnerMatrix(20,66) = -groebnerMatrix(17,75)/(groebnerMatrix(17,52)); groebnerMatrix(20,67) = -groebnerMatrix(17,76)/(groebnerMatrix(17,52)); groebnerMatrix(20,68) = -groebnerMatrix(17,77)/(groebnerMatrix(17,52)); groebnerMatrix(20,69) = groebnerMatrix(13,74)/(groebnerMatrix(13,42)); groebnerMatrix(20,70) = groebnerMatrix(13,75)/(groebnerMatrix(13,42)); groebnerMatrix(20,71) = groebnerMatrix(13,76)/(groebnerMatrix(13,42)); groebnerMatrix(20,72) = (groebnerMatrix(13,77)/(groebnerMatrix(13,42))-groebnerMatrix(17,78)/(groebnerMatrix(17,52))); groebnerMatrix(20,73) = groebnerMatrix(13,78)/(groebnerMatrix(13,42)); groebnerMatrix(20,77) = -groebnerMatrix(17,79)/(groebnerMatrix(17,52)); groebnerMatrix(20,78) = groebnerMatrix(13,79)/(groebnerMatrix(13,42)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial21( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(21,10) = groebnerMatrix(13,43)/(groebnerMatrix(13,42)); groebnerMatrix(21,14) = -groebnerMatrix(18,54)/(groebnerMatrix(18,53)); groebnerMatrix(21,15) = -groebnerMatrix(18,55)/(groebnerMatrix(18,53)); groebnerMatrix(21,16) = -groebnerMatrix(18,56)/(groebnerMatrix(18,53)); groebnerMatrix(21,17) = groebnerMatrix(13,50)/(groebnerMatrix(13,42)); groebnerMatrix(21,18) = groebnerMatrix(13,51)/(groebnerMatrix(13,42)); groebnerMatrix(21,19) = (groebnerMatrix(13,52)/(groebnerMatrix(13,42))-groebnerMatrix(18,57)/(groebnerMatrix(18,53))); groebnerMatrix(21,20) = groebnerMatrix(13,53)/(groebnerMatrix(13,42)); groebnerMatrix(21,21) = groebnerMatrix(13,54)/(groebnerMatrix(13,42)); groebnerMatrix(21,22) = groebnerMatrix(13,55)/(groebnerMatrix(13,42)); groebnerMatrix(21,23) = (groebnerMatrix(13,56)/(groebnerMatrix(13,42))-groebnerMatrix(18,58)/(groebnerMatrix(18,53))); groebnerMatrix(21,24) = groebnerMatrix(13,57)/(groebnerMatrix(13,42)); groebnerMatrix(21,25) = groebnerMatrix(13,58)/(groebnerMatrix(13,42)); groebnerMatrix(21,37) = -groebnerMatrix(18,65)/(groebnerMatrix(18,53)); groebnerMatrix(21,38) = -groebnerMatrix(18,66)/(groebnerMatrix(18,53)); groebnerMatrix(21,39) = -groebnerMatrix(18,67)/(groebnerMatrix(18,53)); groebnerMatrix(21,42) = -groebnerMatrix(18,68)/(groebnerMatrix(18,53)); groebnerMatrix(21,47) = -groebnerMatrix(18,69)/(groebnerMatrix(18,53)); groebnerMatrix(21,48) = -groebnerMatrix(18,70)/(groebnerMatrix(18,53)); groebnerMatrix(21,49) = -groebnerMatrix(18,71)/(groebnerMatrix(18,53)); groebnerMatrix(21,50) = groebnerMatrix(13,65)/(groebnerMatrix(13,42)); groebnerMatrix(21,51) = groebnerMatrix(13,66)/(groebnerMatrix(13,42)); groebnerMatrix(21,52) = (groebnerMatrix(13,67)/(groebnerMatrix(13,42))-groebnerMatrix(18,72)/(groebnerMatrix(18,53))); groebnerMatrix(21,53) = groebnerMatrix(13,68)/(groebnerMatrix(13,42)); groebnerMatrix(21,54) = groebnerMatrix(13,69)/(groebnerMatrix(13,42)); groebnerMatrix(21,55) = groebnerMatrix(13,70)/(groebnerMatrix(13,42)); groebnerMatrix(21,56) = (groebnerMatrix(13,71)/(groebnerMatrix(13,42))-groebnerMatrix(18,73)/(groebnerMatrix(18,53))); groebnerMatrix(21,57) = groebnerMatrix(13,72)/(groebnerMatrix(13,42)); groebnerMatrix(21,58) = groebnerMatrix(13,73)/(groebnerMatrix(13,42)); groebnerMatrix(21,62) = -groebnerMatrix(18,74)/(groebnerMatrix(18,53)); groebnerMatrix(21,63) = -groebnerMatrix(18,75)/(groebnerMatrix(18,53)); groebnerMatrix(21,64) = -groebnerMatrix(18,76)/(groebnerMatrix(18,53)); groebnerMatrix(21,67) = -groebnerMatrix(18,77)/(groebnerMatrix(18,53)); groebnerMatrix(21,69) = groebnerMatrix(13,74)/(groebnerMatrix(13,42)); groebnerMatrix(21,70) = groebnerMatrix(13,75)/(groebnerMatrix(13,42)); groebnerMatrix(21,71) = (groebnerMatrix(13,76)/(groebnerMatrix(13,42))-groebnerMatrix(18,78)/(groebnerMatrix(18,53))); groebnerMatrix(21,72) = groebnerMatrix(13,77)/(groebnerMatrix(13,42)); groebnerMatrix(21,73) = groebnerMatrix(13,78)/(groebnerMatrix(13,42)); groebnerMatrix(21,76) = -groebnerMatrix(18,79)/(groebnerMatrix(18,53)); groebnerMatrix(21,78) = groebnerMatrix(13,79)/(groebnerMatrix(13,42)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial22( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(22,9) = (groebnerMatrix(12,42)/(groebnerMatrix(12,41))-groebnerMatrix(16,52)/(groebnerMatrix(16,51))); groebnerMatrix(22,10) = (groebnerMatrix(12,43)/(groebnerMatrix(12,41))-groebnerMatrix(16,53)/(groebnerMatrix(16,51))); groebnerMatrix(22,17) = (groebnerMatrix(12,50)/(groebnerMatrix(12,41))-groebnerMatrix(16,54)/(groebnerMatrix(16,51))); groebnerMatrix(22,18) = (groebnerMatrix(12,51)/(groebnerMatrix(12,41))-groebnerMatrix(16,55)/(groebnerMatrix(16,51))); groebnerMatrix(22,19) = (groebnerMatrix(12,52)/(groebnerMatrix(12,41))-groebnerMatrix(16,56)/(groebnerMatrix(16,51))); groebnerMatrix(22,20) = (groebnerMatrix(12,53)/(groebnerMatrix(12,41))-groebnerMatrix(16,57)/(groebnerMatrix(16,51))); groebnerMatrix(22,21) = groebnerMatrix(12,54)/(groebnerMatrix(12,41)); groebnerMatrix(22,22) = groebnerMatrix(12,55)/(groebnerMatrix(12,41)); groebnerMatrix(22,23) = groebnerMatrix(12,56)/(groebnerMatrix(12,41)); groebnerMatrix(22,24) = (groebnerMatrix(12,57)/(groebnerMatrix(12,41))-groebnerMatrix(16,58)/(groebnerMatrix(16,51))); groebnerMatrix(22,25) = groebnerMatrix(12,58)/(groebnerMatrix(12,41)); groebnerMatrix(22,40) = -groebnerMatrix(16,65)/(groebnerMatrix(16,51)); groebnerMatrix(22,41) = -groebnerMatrix(16,66)/(groebnerMatrix(16,51)); groebnerMatrix(22,42) = -groebnerMatrix(16,67)/(groebnerMatrix(16,51)); groebnerMatrix(22,43) = -groebnerMatrix(16,68)/(groebnerMatrix(16,51)); groebnerMatrix(22,50) = (groebnerMatrix(12,65)/(groebnerMatrix(12,41))-groebnerMatrix(16,69)/(groebnerMatrix(16,51))); groebnerMatrix(22,51) = (groebnerMatrix(12,66)/(groebnerMatrix(12,41))-groebnerMatrix(16,70)/(groebnerMatrix(16,51))); groebnerMatrix(22,52) = (groebnerMatrix(12,67)/(groebnerMatrix(12,41))-groebnerMatrix(16,71)/(groebnerMatrix(16,51))); groebnerMatrix(22,53) = (groebnerMatrix(12,68)/(groebnerMatrix(12,41))-groebnerMatrix(16,72)/(groebnerMatrix(16,51))); groebnerMatrix(22,54) = groebnerMatrix(12,69)/(groebnerMatrix(12,41)); groebnerMatrix(22,55) = groebnerMatrix(12,70)/(groebnerMatrix(12,41)); groebnerMatrix(22,56) = groebnerMatrix(12,71)/(groebnerMatrix(12,41)); groebnerMatrix(22,57) = (groebnerMatrix(12,72)/(groebnerMatrix(12,41))-groebnerMatrix(16,73)/(groebnerMatrix(16,51))); groebnerMatrix(22,58) = groebnerMatrix(12,73)/(groebnerMatrix(12,41)); groebnerMatrix(22,65) = -groebnerMatrix(16,74)/(groebnerMatrix(16,51)); groebnerMatrix(22,66) = -groebnerMatrix(16,75)/(groebnerMatrix(16,51)); groebnerMatrix(22,67) = -groebnerMatrix(16,76)/(groebnerMatrix(16,51)); groebnerMatrix(22,68) = -groebnerMatrix(16,77)/(groebnerMatrix(16,51)); groebnerMatrix(22,69) = groebnerMatrix(12,74)/(groebnerMatrix(12,41)); groebnerMatrix(22,70) = groebnerMatrix(12,75)/(groebnerMatrix(12,41)); groebnerMatrix(22,71) = groebnerMatrix(12,76)/(groebnerMatrix(12,41)); groebnerMatrix(22,72) = (groebnerMatrix(12,77)/(groebnerMatrix(12,41))-groebnerMatrix(16,78)/(groebnerMatrix(16,51))); groebnerMatrix(22,73) = groebnerMatrix(12,78)/(groebnerMatrix(12,41)); groebnerMatrix(22,77) = -groebnerMatrix(16,79)/(groebnerMatrix(16,51)); groebnerMatrix(22,78) = groebnerMatrix(12,79)/(groebnerMatrix(12,41)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial23( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(23,9) = groebnerMatrix(12,42)/(groebnerMatrix(12,41)); groebnerMatrix(23,10) = groebnerMatrix(12,43)/(groebnerMatrix(12,41)); groebnerMatrix(23,12) = -groebnerMatrix(18,54)/(groebnerMatrix(18,53)); groebnerMatrix(23,13) = -groebnerMatrix(18,55)/(groebnerMatrix(18,53)); groebnerMatrix(23,15) = -groebnerMatrix(18,56)/(groebnerMatrix(18,53)); groebnerMatrix(23,17) = groebnerMatrix(12,50)/(groebnerMatrix(12,41)); groebnerMatrix(23,18) = (groebnerMatrix(12,51)/(groebnerMatrix(12,41))-groebnerMatrix(18,57)/(groebnerMatrix(18,53))); groebnerMatrix(23,19) = groebnerMatrix(12,52)/(groebnerMatrix(12,41)); groebnerMatrix(23,20) = groebnerMatrix(12,53)/(groebnerMatrix(12,41)); groebnerMatrix(23,21) = groebnerMatrix(12,54)/(groebnerMatrix(12,41)); groebnerMatrix(23,22) = (groebnerMatrix(12,55)/(groebnerMatrix(12,41))-groebnerMatrix(18,58)/(groebnerMatrix(18,53))); groebnerMatrix(23,23) = groebnerMatrix(12,56)/(groebnerMatrix(12,41)); groebnerMatrix(23,24) = groebnerMatrix(12,57)/(groebnerMatrix(12,41)); groebnerMatrix(23,25) = groebnerMatrix(12,58)/(groebnerMatrix(12,41)); groebnerMatrix(23,35) = -groebnerMatrix(18,65)/(groebnerMatrix(18,53)); groebnerMatrix(23,36) = -groebnerMatrix(18,66)/(groebnerMatrix(18,53)); groebnerMatrix(23,38) = -groebnerMatrix(18,67)/(groebnerMatrix(18,53)); groebnerMatrix(23,41) = -groebnerMatrix(18,68)/(groebnerMatrix(18,53)); groebnerMatrix(23,45) = -groebnerMatrix(18,69)/(groebnerMatrix(18,53)); groebnerMatrix(23,46) = -groebnerMatrix(18,70)/(groebnerMatrix(18,53)); groebnerMatrix(23,48) = -groebnerMatrix(18,71)/(groebnerMatrix(18,53)); groebnerMatrix(23,50) = groebnerMatrix(12,65)/(groebnerMatrix(12,41)); groebnerMatrix(23,51) = (groebnerMatrix(12,66)/(groebnerMatrix(12,41))-groebnerMatrix(18,72)/(groebnerMatrix(18,53))); groebnerMatrix(23,52) = groebnerMatrix(12,67)/(groebnerMatrix(12,41)); groebnerMatrix(23,53) = groebnerMatrix(12,68)/(groebnerMatrix(12,41)); groebnerMatrix(23,54) = groebnerMatrix(12,69)/(groebnerMatrix(12,41)); groebnerMatrix(23,55) = (groebnerMatrix(12,70)/(groebnerMatrix(12,41))-groebnerMatrix(18,73)/(groebnerMatrix(18,53))); groebnerMatrix(23,56) = groebnerMatrix(12,71)/(groebnerMatrix(12,41)); groebnerMatrix(23,57) = groebnerMatrix(12,72)/(groebnerMatrix(12,41)); groebnerMatrix(23,58) = groebnerMatrix(12,73)/(groebnerMatrix(12,41)); groebnerMatrix(23,60) = -groebnerMatrix(18,74)/(groebnerMatrix(18,53)); groebnerMatrix(23,61) = -groebnerMatrix(18,75)/(groebnerMatrix(18,53)); groebnerMatrix(23,63) = -groebnerMatrix(18,76)/(groebnerMatrix(18,53)); groebnerMatrix(23,66) = -groebnerMatrix(18,77)/(groebnerMatrix(18,53)); groebnerMatrix(23,69) = groebnerMatrix(12,74)/(groebnerMatrix(12,41)); groebnerMatrix(23,70) = (groebnerMatrix(12,75)/(groebnerMatrix(12,41))-groebnerMatrix(18,78)/(groebnerMatrix(18,53))); groebnerMatrix(23,71) = groebnerMatrix(12,76)/(groebnerMatrix(12,41)); groebnerMatrix(23,72) = groebnerMatrix(12,77)/(groebnerMatrix(12,41)); groebnerMatrix(23,73) = groebnerMatrix(12,78)/(groebnerMatrix(12,41)); groebnerMatrix(23,75) = -groebnerMatrix(18,79)/(groebnerMatrix(18,53)); groebnerMatrix(23,78) = groebnerMatrix(12,79)/(groebnerMatrix(12,41)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial24( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(24,8) = (groebnerMatrix(11,41)/(groebnerMatrix(11,40))-groebnerMatrix(15,51)/(groebnerMatrix(15,50))); groebnerMatrix(24,9) = (groebnerMatrix(11,42)/(groebnerMatrix(11,40))-groebnerMatrix(15,52)/(groebnerMatrix(15,50))); groebnerMatrix(24,10) = (groebnerMatrix(11,43)/(groebnerMatrix(11,40))-groebnerMatrix(15,53)/(groebnerMatrix(15,50))); groebnerMatrix(24,17) = (groebnerMatrix(11,50)/(groebnerMatrix(11,40))-groebnerMatrix(15,54)/(groebnerMatrix(15,50))); groebnerMatrix(24,18) = (groebnerMatrix(11,51)/(groebnerMatrix(11,40))-groebnerMatrix(15,55)/(groebnerMatrix(15,50))); groebnerMatrix(24,19) = (groebnerMatrix(11,52)/(groebnerMatrix(11,40))-groebnerMatrix(15,56)/(groebnerMatrix(15,50))); groebnerMatrix(24,20) = (groebnerMatrix(11,53)/(groebnerMatrix(11,40))-groebnerMatrix(15,57)/(groebnerMatrix(15,50))); groebnerMatrix(24,21) = groebnerMatrix(11,54)/(groebnerMatrix(11,40)); groebnerMatrix(24,22) = groebnerMatrix(11,55)/(groebnerMatrix(11,40)); groebnerMatrix(24,23) = groebnerMatrix(11,56)/(groebnerMatrix(11,40)); groebnerMatrix(24,24) = (groebnerMatrix(11,57)/(groebnerMatrix(11,40))-groebnerMatrix(15,58)/(groebnerMatrix(15,50))); groebnerMatrix(24,25) = groebnerMatrix(11,58)/(groebnerMatrix(11,40)); groebnerMatrix(24,40) = -groebnerMatrix(15,65)/(groebnerMatrix(15,50)); groebnerMatrix(24,41) = -groebnerMatrix(15,66)/(groebnerMatrix(15,50)); groebnerMatrix(24,42) = -groebnerMatrix(15,67)/(groebnerMatrix(15,50)); groebnerMatrix(24,43) = -groebnerMatrix(15,68)/(groebnerMatrix(15,50)); groebnerMatrix(24,50) = (groebnerMatrix(11,65)/(groebnerMatrix(11,40))-groebnerMatrix(15,69)/(groebnerMatrix(15,50))); groebnerMatrix(24,51) = (groebnerMatrix(11,66)/(groebnerMatrix(11,40))-groebnerMatrix(15,70)/(groebnerMatrix(15,50))); groebnerMatrix(24,52) = (groebnerMatrix(11,67)/(groebnerMatrix(11,40))-groebnerMatrix(15,71)/(groebnerMatrix(15,50))); groebnerMatrix(24,53) = (groebnerMatrix(11,68)/(groebnerMatrix(11,40))-groebnerMatrix(15,72)/(groebnerMatrix(15,50))); groebnerMatrix(24,54) = groebnerMatrix(11,69)/(groebnerMatrix(11,40)); groebnerMatrix(24,55) = groebnerMatrix(11,70)/(groebnerMatrix(11,40)); groebnerMatrix(24,56) = groebnerMatrix(11,71)/(groebnerMatrix(11,40)); groebnerMatrix(24,57) = (groebnerMatrix(11,72)/(groebnerMatrix(11,40))-groebnerMatrix(15,73)/(groebnerMatrix(15,50))); groebnerMatrix(24,58) = groebnerMatrix(11,73)/(groebnerMatrix(11,40)); groebnerMatrix(24,65) = -groebnerMatrix(15,74)/(groebnerMatrix(15,50)); groebnerMatrix(24,66) = -groebnerMatrix(15,75)/(groebnerMatrix(15,50)); groebnerMatrix(24,67) = -groebnerMatrix(15,76)/(groebnerMatrix(15,50)); groebnerMatrix(24,68) = -groebnerMatrix(15,77)/(groebnerMatrix(15,50)); groebnerMatrix(24,69) = groebnerMatrix(11,74)/(groebnerMatrix(11,40)); groebnerMatrix(24,70) = groebnerMatrix(11,75)/(groebnerMatrix(11,40)); groebnerMatrix(24,71) = groebnerMatrix(11,76)/(groebnerMatrix(11,40)); groebnerMatrix(24,72) = (groebnerMatrix(11,77)/(groebnerMatrix(11,40))-groebnerMatrix(15,78)/(groebnerMatrix(15,50))); groebnerMatrix(24,73) = groebnerMatrix(11,78)/(groebnerMatrix(11,40)); groebnerMatrix(24,77) = -groebnerMatrix(15,79)/(groebnerMatrix(15,50)); groebnerMatrix(24,78) = groebnerMatrix(11,79)/(groebnerMatrix(11,40)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial25( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(25,8) = groebnerMatrix(11,41)/(groebnerMatrix(11,40)); groebnerMatrix(25,9) = groebnerMatrix(11,42)/(groebnerMatrix(11,40)); groebnerMatrix(25,10) = groebnerMatrix(11,43)/(groebnerMatrix(11,40)); groebnerMatrix(25,11) = -groebnerMatrix(18,54)/(groebnerMatrix(18,53)); groebnerMatrix(25,12) = -groebnerMatrix(18,55)/(groebnerMatrix(18,53)); groebnerMatrix(25,14) = -groebnerMatrix(18,56)/(groebnerMatrix(18,53)); groebnerMatrix(25,17) = (groebnerMatrix(11,50)/(groebnerMatrix(11,40))-groebnerMatrix(18,57)/(groebnerMatrix(18,53))); groebnerMatrix(25,18) = groebnerMatrix(11,51)/(groebnerMatrix(11,40)); groebnerMatrix(25,19) = groebnerMatrix(11,52)/(groebnerMatrix(11,40)); groebnerMatrix(25,20) = groebnerMatrix(11,53)/(groebnerMatrix(11,40)); groebnerMatrix(25,21) = (groebnerMatrix(11,54)/(groebnerMatrix(11,40))-groebnerMatrix(18,58)/(groebnerMatrix(18,53))); groebnerMatrix(25,22) = groebnerMatrix(11,55)/(groebnerMatrix(11,40)); groebnerMatrix(25,23) = groebnerMatrix(11,56)/(groebnerMatrix(11,40)); groebnerMatrix(25,24) = groebnerMatrix(11,57)/(groebnerMatrix(11,40)); groebnerMatrix(25,25) = groebnerMatrix(11,58)/(groebnerMatrix(11,40)); groebnerMatrix(25,34) = -groebnerMatrix(18,65)/(groebnerMatrix(18,53)); groebnerMatrix(25,35) = -groebnerMatrix(18,66)/(groebnerMatrix(18,53)); groebnerMatrix(25,37) = -groebnerMatrix(18,67)/(groebnerMatrix(18,53)); groebnerMatrix(25,40) = -groebnerMatrix(18,68)/(groebnerMatrix(18,53)); groebnerMatrix(25,44) = -groebnerMatrix(18,69)/(groebnerMatrix(18,53)); groebnerMatrix(25,45) = -groebnerMatrix(18,70)/(groebnerMatrix(18,53)); groebnerMatrix(25,47) = -groebnerMatrix(18,71)/(groebnerMatrix(18,53)); groebnerMatrix(25,50) = (groebnerMatrix(11,65)/(groebnerMatrix(11,40))-groebnerMatrix(18,72)/(groebnerMatrix(18,53))); groebnerMatrix(25,51) = groebnerMatrix(11,66)/(groebnerMatrix(11,40)); groebnerMatrix(25,52) = groebnerMatrix(11,67)/(groebnerMatrix(11,40)); groebnerMatrix(25,53) = groebnerMatrix(11,68)/(groebnerMatrix(11,40)); groebnerMatrix(25,54) = (groebnerMatrix(11,69)/(groebnerMatrix(11,40))-groebnerMatrix(18,73)/(groebnerMatrix(18,53))); groebnerMatrix(25,55) = groebnerMatrix(11,70)/(groebnerMatrix(11,40)); groebnerMatrix(25,56) = groebnerMatrix(11,71)/(groebnerMatrix(11,40)); groebnerMatrix(25,57) = groebnerMatrix(11,72)/(groebnerMatrix(11,40)); groebnerMatrix(25,58) = groebnerMatrix(11,73)/(groebnerMatrix(11,40)); groebnerMatrix(25,59) = -groebnerMatrix(18,74)/(groebnerMatrix(18,53)); groebnerMatrix(25,60) = -groebnerMatrix(18,75)/(groebnerMatrix(18,53)); groebnerMatrix(25,62) = -groebnerMatrix(18,76)/(groebnerMatrix(18,53)); groebnerMatrix(25,65) = -groebnerMatrix(18,77)/(groebnerMatrix(18,53)); groebnerMatrix(25,69) = (groebnerMatrix(11,74)/(groebnerMatrix(11,40))-groebnerMatrix(18,78)/(groebnerMatrix(18,53))); groebnerMatrix(25,70) = groebnerMatrix(11,75)/(groebnerMatrix(11,40)); groebnerMatrix(25,71) = groebnerMatrix(11,76)/(groebnerMatrix(11,40)); groebnerMatrix(25,72) = groebnerMatrix(11,77)/(groebnerMatrix(11,40)); groebnerMatrix(25,73) = groebnerMatrix(11,78)/(groebnerMatrix(11,40)); groebnerMatrix(25,74) = -groebnerMatrix(18,79)/(groebnerMatrix(18,53)); groebnerMatrix(25,78) = groebnerMatrix(11,79)/(groebnerMatrix(11,40)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial26( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(26,7) = groebnerMatrix(10,65)/(groebnerMatrix(10,64)); groebnerMatrix(26,8) = groebnerMatrix(10,66)/(groebnerMatrix(10,64)); groebnerMatrix(26,9) = (groebnerMatrix(10,67)/(groebnerMatrix(10,64))-groebnerMatrix(17,53)/(groebnerMatrix(17,52))); groebnerMatrix(26,10) = groebnerMatrix(10,68)/(groebnerMatrix(10,64)); groebnerMatrix(26,14) = -groebnerMatrix(17,54)/(groebnerMatrix(17,52)); groebnerMatrix(26,15) = -groebnerMatrix(17,55)/(groebnerMatrix(17,52)); groebnerMatrix(26,16) = -groebnerMatrix(17,56)/(groebnerMatrix(17,52)); groebnerMatrix(26,17) = groebnerMatrix(10,69)/(groebnerMatrix(10,64)); groebnerMatrix(26,18) = groebnerMatrix(10,70)/(groebnerMatrix(10,64)); groebnerMatrix(26,19) = (groebnerMatrix(10,71)/(groebnerMatrix(10,64))-groebnerMatrix(17,57)/(groebnerMatrix(17,52))); groebnerMatrix(26,20) = groebnerMatrix(10,72)/(groebnerMatrix(10,64)); groebnerMatrix(26,23) = -groebnerMatrix(17,58)/(groebnerMatrix(17,52)); groebnerMatrix(26,24) = groebnerMatrix(10,73)/(groebnerMatrix(10,64)); groebnerMatrix(26,37) = -groebnerMatrix(17,65)/(groebnerMatrix(17,52)); groebnerMatrix(26,38) = -groebnerMatrix(17,66)/(groebnerMatrix(17,52)); groebnerMatrix(26,39) = -groebnerMatrix(17,67)/(groebnerMatrix(17,52)); groebnerMatrix(26,42) = -groebnerMatrix(17,68)/(groebnerMatrix(17,52)); groebnerMatrix(26,47) = -groebnerMatrix(17,69)/(groebnerMatrix(17,52)); groebnerMatrix(26,48) = -groebnerMatrix(17,70)/(groebnerMatrix(17,52)); groebnerMatrix(26,49) = -groebnerMatrix(17,71)/(groebnerMatrix(17,52)); groebnerMatrix(26,50) = groebnerMatrix(10,74)/(groebnerMatrix(10,64)); groebnerMatrix(26,51) = groebnerMatrix(10,75)/(groebnerMatrix(10,64)); groebnerMatrix(26,52) = (groebnerMatrix(10,76)/(groebnerMatrix(10,64))-groebnerMatrix(17,72)/(groebnerMatrix(17,52))); groebnerMatrix(26,53) = groebnerMatrix(10,77)/(groebnerMatrix(10,64)); groebnerMatrix(26,56) = -groebnerMatrix(17,73)/(groebnerMatrix(17,52)); groebnerMatrix(26,57) = groebnerMatrix(10,78)/(groebnerMatrix(10,64)); groebnerMatrix(26,62) = -groebnerMatrix(17,74)/(groebnerMatrix(17,52)); groebnerMatrix(26,63) = -groebnerMatrix(17,75)/(groebnerMatrix(17,52)); groebnerMatrix(26,64) = -groebnerMatrix(17,76)/(groebnerMatrix(17,52)); groebnerMatrix(26,67) = -groebnerMatrix(17,77)/(groebnerMatrix(17,52)); groebnerMatrix(26,71) = -groebnerMatrix(17,78)/(groebnerMatrix(17,52)); groebnerMatrix(26,72) = groebnerMatrix(10,79)/(groebnerMatrix(10,64)); groebnerMatrix(26,76) = -groebnerMatrix(17,79)/(groebnerMatrix(17,52)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial27( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(27,6) = (groebnerMatrix(9,64)/(groebnerMatrix(9,63))-groebnerMatrix(16,52)/(groebnerMatrix(16,51))); groebnerMatrix(27,7) = groebnerMatrix(9,65)/(groebnerMatrix(9,63)); groebnerMatrix(27,8) = groebnerMatrix(9,66)/(groebnerMatrix(9,63)); groebnerMatrix(27,9) = (groebnerMatrix(9,67)/(groebnerMatrix(9,63))-groebnerMatrix(16,53)/(groebnerMatrix(16,51))); groebnerMatrix(27,10) = groebnerMatrix(9,68)/(groebnerMatrix(9,63)); groebnerMatrix(27,14) = -groebnerMatrix(16,54)/(groebnerMatrix(16,51)); groebnerMatrix(27,15) = -groebnerMatrix(16,55)/(groebnerMatrix(16,51)); groebnerMatrix(27,16) = -groebnerMatrix(16,56)/(groebnerMatrix(16,51)); groebnerMatrix(27,17) = groebnerMatrix(9,69)/(groebnerMatrix(9,63)); groebnerMatrix(27,18) = groebnerMatrix(9,70)/(groebnerMatrix(9,63)); groebnerMatrix(27,19) = (groebnerMatrix(9,71)/(groebnerMatrix(9,63))-groebnerMatrix(16,57)/(groebnerMatrix(16,51))); groebnerMatrix(27,20) = groebnerMatrix(9,72)/(groebnerMatrix(9,63)); groebnerMatrix(27,23) = -groebnerMatrix(16,58)/(groebnerMatrix(16,51)); groebnerMatrix(27,24) = groebnerMatrix(9,73)/(groebnerMatrix(9,63)); groebnerMatrix(27,37) = -groebnerMatrix(16,65)/(groebnerMatrix(16,51)); groebnerMatrix(27,38) = -groebnerMatrix(16,66)/(groebnerMatrix(16,51)); groebnerMatrix(27,39) = -groebnerMatrix(16,67)/(groebnerMatrix(16,51)); groebnerMatrix(27,42) = -groebnerMatrix(16,68)/(groebnerMatrix(16,51)); groebnerMatrix(27,47) = -groebnerMatrix(16,69)/(groebnerMatrix(16,51)); groebnerMatrix(27,48) = -groebnerMatrix(16,70)/(groebnerMatrix(16,51)); groebnerMatrix(27,49) = -groebnerMatrix(16,71)/(groebnerMatrix(16,51)); groebnerMatrix(27,50) = groebnerMatrix(9,74)/(groebnerMatrix(9,63)); groebnerMatrix(27,51) = groebnerMatrix(9,75)/(groebnerMatrix(9,63)); groebnerMatrix(27,52) = (groebnerMatrix(9,76)/(groebnerMatrix(9,63))-groebnerMatrix(16,72)/(groebnerMatrix(16,51))); groebnerMatrix(27,53) = groebnerMatrix(9,77)/(groebnerMatrix(9,63)); groebnerMatrix(27,56) = -groebnerMatrix(16,73)/(groebnerMatrix(16,51)); groebnerMatrix(27,57) = groebnerMatrix(9,78)/(groebnerMatrix(9,63)); groebnerMatrix(27,62) = -groebnerMatrix(16,74)/(groebnerMatrix(16,51)); groebnerMatrix(27,63) = -groebnerMatrix(16,75)/(groebnerMatrix(16,51)); groebnerMatrix(27,64) = -groebnerMatrix(16,76)/(groebnerMatrix(16,51)); groebnerMatrix(27,67) = -groebnerMatrix(16,77)/(groebnerMatrix(16,51)); groebnerMatrix(27,71) = -groebnerMatrix(16,78)/(groebnerMatrix(16,51)); groebnerMatrix(27,72) = groebnerMatrix(9,79)/(groebnerMatrix(9,63)); groebnerMatrix(27,76) = -groebnerMatrix(16,79)/(groebnerMatrix(16,51)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial28( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(28,6) = groebnerMatrix(9,64)/(groebnerMatrix(9,63)); groebnerMatrix(28,7) = groebnerMatrix(9,65)/(groebnerMatrix(9,63)); groebnerMatrix(28,8) = (groebnerMatrix(9,66)/(groebnerMatrix(9,63))-groebnerMatrix(17,53)/(groebnerMatrix(17,52))); groebnerMatrix(28,9) = groebnerMatrix(9,67)/(groebnerMatrix(9,63)); groebnerMatrix(28,10) = groebnerMatrix(9,68)/(groebnerMatrix(9,63)); groebnerMatrix(28,12) = -groebnerMatrix(17,54)/(groebnerMatrix(17,52)); groebnerMatrix(28,13) = -groebnerMatrix(17,55)/(groebnerMatrix(17,52)); groebnerMatrix(28,15) = -groebnerMatrix(17,56)/(groebnerMatrix(17,52)); groebnerMatrix(28,17) = groebnerMatrix(9,69)/(groebnerMatrix(9,63)); groebnerMatrix(28,18) = (groebnerMatrix(9,70)/(groebnerMatrix(9,63))-groebnerMatrix(17,57)/(groebnerMatrix(17,52))); groebnerMatrix(28,19) = groebnerMatrix(9,71)/(groebnerMatrix(9,63)); groebnerMatrix(28,20) = groebnerMatrix(9,72)/(groebnerMatrix(9,63)); groebnerMatrix(28,22) = -groebnerMatrix(17,58)/(groebnerMatrix(17,52)); groebnerMatrix(28,24) = groebnerMatrix(9,73)/(groebnerMatrix(9,63)); groebnerMatrix(28,35) = -groebnerMatrix(17,65)/(groebnerMatrix(17,52)); groebnerMatrix(28,36) = -groebnerMatrix(17,66)/(groebnerMatrix(17,52)); groebnerMatrix(28,38) = -groebnerMatrix(17,67)/(groebnerMatrix(17,52)); groebnerMatrix(28,41) = -groebnerMatrix(17,68)/(groebnerMatrix(17,52)); groebnerMatrix(28,45) = -groebnerMatrix(17,69)/(groebnerMatrix(17,52)); groebnerMatrix(28,46) = -groebnerMatrix(17,70)/(groebnerMatrix(17,52)); groebnerMatrix(28,48) = -groebnerMatrix(17,71)/(groebnerMatrix(17,52)); groebnerMatrix(28,50) = groebnerMatrix(9,74)/(groebnerMatrix(9,63)); groebnerMatrix(28,51) = (groebnerMatrix(9,75)/(groebnerMatrix(9,63))-groebnerMatrix(17,72)/(groebnerMatrix(17,52))); groebnerMatrix(28,52) = groebnerMatrix(9,76)/(groebnerMatrix(9,63)); groebnerMatrix(28,53) = groebnerMatrix(9,77)/(groebnerMatrix(9,63)); groebnerMatrix(28,55) = -groebnerMatrix(17,73)/(groebnerMatrix(17,52)); groebnerMatrix(28,57) = groebnerMatrix(9,78)/(groebnerMatrix(9,63)); groebnerMatrix(28,60) = -groebnerMatrix(17,74)/(groebnerMatrix(17,52)); groebnerMatrix(28,61) = -groebnerMatrix(17,75)/(groebnerMatrix(17,52)); groebnerMatrix(28,63) = -groebnerMatrix(17,76)/(groebnerMatrix(17,52)); groebnerMatrix(28,66) = -groebnerMatrix(17,77)/(groebnerMatrix(17,52)); groebnerMatrix(28,70) = -groebnerMatrix(17,78)/(groebnerMatrix(17,52)); groebnerMatrix(28,72) = groebnerMatrix(9,79)/(groebnerMatrix(9,63)); groebnerMatrix(28,75) = -groebnerMatrix(17,79)/(groebnerMatrix(17,52)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial29( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(29,5) = (groebnerMatrix(8,63)/(groebnerMatrix(8,62))-groebnerMatrix(15,51)/(groebnerMatrix(15,50))); groebnerMatrix(29,6) = (groebnerMatrix(8,64)/(groebnerMatrix(8,62))-groebnerMatrix(15,52)/(groebnerMatrix(15,50))); groebnerMatrix(29,7) = groebnerMatrix(8,65)/(groebnerMatrix(8,62)); groebnerMatrix(29,8) = groebnerMatrix(8,66)/(groebnerMatrix(8,62)); groebnerMatrix(29,9) = (groebnerMatrix(8,67)/(groebnerMatrix(8,62))-groebnerMatrix(15,53)/(groebnerMatrix(15,50))); groebnerMatrix(29,10) = groebnerMatrix(8,68)/(groebnerMatrix(8,62)); groebnerMatrix(29,14) = -groebnerMatrix(15,54)/(groebnerMatrix(15,50)); groebnerMatrix(29,15) = -groebnerMatrix(15,55)/(groebnerMatrix(15,50)); groebnerMatrix(29,16) = -groebnerMatrix(15,56)/(groebnerMatrix(15,50)); groebnerMatrix(29,17) = groebnerMatrix(8,69)/(groebnerMatrix(8,62)); groebnerMatrix(29,18) = groebnerMatrix(8,70)/(groebnerMatrix(8,62)); groebnerMatrix(29,19) = (groebnerMatrix(8,71)/(groebnerMatrix(8,62))-groebnerMatrix(15,57)/(groebnerMatrix(15,50))); groebnerMatrix(29,20) = groebnerMatrix(8,72)/(groebnerMatrix(8,62)); groebnerMatrix(29,23) = -groebnerMatrix(15,58)/(groebnerMatrix(15,50)); groebnerMatrix(29,24) = groebnerMatrix(8,73)/(groebnerMatrix(8,62)); groebnerMatrix(29,37) = -groebnerMatrix(15,65)/(groebnerMatrix(15,50)); groebnerMatrix(29,38) = -groebnerMatrix(15,66)/(groebnerMatrix(15,50)); groebnerMatrix(29,39) = -groebnerMatrix(15,67)/(groebnerMatrix(15,50)); groebnerMatrix(29,42) = -groebnerMatrix(15,68)/(groebnerMatrix(15,50)); groebnerMatrix(29,47) = -groebnerMatrix(15,69)/(groebnerMatrix(15,50)); groebnerMatrix(29,48) = -groebnerMatrix(15,70)/(groebnerMatrix(15,50)); groebnerMatrix(29,49) = -groebnerMatrix(15,71)/(groebnerMatrix(15,50)); groebnerMatrix(29,50) = groebnerMatrix(8,74)/(groebnerMatrix(8,62)); groebnerMatrix(29,51) = groebnerMatrix(8,75)/(groebnerMatrix(8,62)); groebnerMatrix(29,52) = (groebnerMatrix(8,76)/(groebnerMatrix(8,62))-groebnerMatrix(15,72)/(groebnerMatrix(15,50))); groebnerMatrix(29,53) = groebnerMatrix(8,77)/(groebnerMatrix(8,62)); groebnerMatrix(29,56) = -groebnerMatrix(15,73)/(groebnerMatrix(15,50)); groebnerMatrix(29,57) = groebnerMatrix(8,78)/(groebnerMatrix(8,62)); groebnerMatrix(29,62) = -groebnerMatrix(15,74)/(groebnerMatrix(15,50)); groebnerMatrix(29,63) = -groebnerMatrix(15,75)/(groebnerMatrix(15,50)); groebnerMatrix(29,64) = -groebnerMatrix(15,76)/(groebnerMatrix(15,50)); groebnerMatrix(29,67) = -groebnerMatrix(15,77)/(groebnerMatrix(15,50)); groebnerMatrix(29,71) = -groebnerMatrix(15,78)/(groebnerMatrix(15,50)); groebnerMatrix(29,72) = groebnerMatrix(8,79)/(groebnerMatrix(8,62)); groebnerMatrix(29,76) = -groebnerMatrix(15,79)/(groebnerMatrix(15,50)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial30( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(30,5) = groebnerMatrix(8,63)/(groebnerMatrix(8,62)); groebnerMatrix(30,6) = groebnerMatrix(8,64)/(groebnerMatrix(8,62)); groebnerMatrix(30,7) = (groebnerMatrix(8,65)/(groebnerMatrix(8,62))-groebnerMatrix(17,53)/(groebnerMatrix(17,52))); groebnerMatrix(30,8) = groebnerMatrix(8,66)/(groebnerMatrix(8,62)); groebnerMatrix(30,9) = groebnerMatrix(8,67)/(groebnerMatrix(8,62)); groebnerMatrix(30,10) = groebnerMatrix(8,68)/(groebnerMatrix(8,62)); groebnerMatrix(30,11) = -groebnerMatrix(17,54)/(groebnerMatrix(17,52)); groebnerMatrix(30,12) = -groebnerMatrix(17,55)/(groebnerMatrix(17,52)); groebnerMatrix(30,14) = -groebnerMatrix(17,56)/(groebnerMatrix(17,52)); groebnerMatrix(30,17) = (groebnerMatrix(8,69)/(groebnerMatrix(8,62))-groebnerMatrix(17,57)/(groebnerMatrix(17,52))); groebnerMatrix(30,18) = groebnerMatrix(8,70)/(groebnerMatrix(8,62)); groebnerMatrix(30,19) = groebnerMatrix(8,71)/(groebnerMatrix(8,62)); groebnerMatrix(30,20) = groebnerMatrix(8,72)/(groebnerMatrix(8,62)); groebnerMatrix(30,21) = -groebnerMatrix(17,58)/(groebnerMatrix(17,52)); groebnerMatrix(30,24) = groebnerMatrix(8,73)/(groebnerMatrix(8,62)); groebnerMatrix(30,34) = -groebnerMatrix(17,65)/(groebnerMatrix(17,52)); groebnerMatrix(30,35) = -groebnerMatrix(17,66)/(groebnerMatrix(17,52)); groebnerMatrix(30,37) = -groebnerMatrix(17,67)/(groebnerMatrix(17,52)); groebnerMatrix(30,40) = -groebnerMatrix(17,68)/(groebnerMatrix(17,52)); groebnerMatrix(30,44) = -groebnerMatrix(17,69)/(groebnerMatrix(17,52)); groebnerMatrix(30,45) = -groebnerMatrix(17,70)/(groebnerMatrix(17,52)); groebnerMatrix(30,47) = -groebnerMatrix(17,71)/(groebnerMatrix(17,52)); groebnerMatrix(30,50) = (groebnerMatrix(8,74)/(groebnerMatrix(8,62))-groebnerMatrix(17,72)/(groebnerMatrix(17,52))); groebnerMatrix(30,51) = groebnerMatrix(8,75)/(groebnerMatrix(8,62)); groebnerMatrix(30,52) = groebnerMatrix(8,76)/(groebnerMatrix(8,62)); groebnerMatrix(30,53) = groebnerMatrix(8,77)/(groebnerMatrix(8,62)); groebnerMatrix(30,54) = -groebnerMatrix(17,73)/(groebnerMatrix(17,52)); groebnerMatrix(30,57) = groebnerMatrix(8,78)/(groebnerMatrix(8,62)); groebnerMatrix(30,59) = -groebnerMatrix(17,74)/(groebnerMatrix(17,52)); groebnerMatrix(30,60) = -groebnerMatrix(17,75)/(groebnerMatrix(17,52)); groebnerMatrix(30,62) = -groebnerMatrix(17,76)/(groebnerMatrix(17,52)); groebnerMatrix(30,65) = -groebnerMatrix(17,77)/(groebnerMatrix(17,52)); groebnerMatrix(30,69) = -groebnerMatrix(17,78)/(groebnerMatrix(17,52)); groebnerMatrix(30,72) = groebnerMatrix(8,79)/(groebnerMatrix(8,62)); groebnerMatrix(30,74) = -groebnerMatrix(17,79)/(groebnerMatrix(17,52)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial31( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(31,1) = groebnerMatrix(13,43)/(groebnerMatrix(13,42)); groebnerMatrix(31,4) = -groebnerMatrix(14,50)/(groebnerMatrix(14,43)); groebnerMatrix(31,5) = -groebnerMatrix(14,51)/(groebnerMatrix(14,43)); groebnerMatrix(31,6) = -groebnerMatrix(14,52)/(groebnerMatrix(14,43)); groebnerMatrix(31,7) = groebnerMatrix(13,50)/(groebnerMatrix(13,42)); groebnerMatrix(31,8) = groebnerMatrix(13,51)/(groebnerMatrix(13,42)); groebnerMatrix(31,9) = (groebnerMatrix(13,52)/(groebnerMatrix(13,42))-groebnerMatrix(14,53)/(groebnerMatrix(14,43))); groebnerMatrix(31,10) = groebnerMatrix(13,53)/(groebnerMatrix(13,42)); groebnerMatrix(31,14) = -groebnerMatrix(14,54)/(groebnerMatrix(14,43)); groebnerMatrix(31,15) = -groebnerMatrix(14,55)/(groebnerMatrix(14,43)); groebnerMatrix(31,16) = -groebnerMatrix(14,56)/(groebnerMatrix(14,43)); groebnerMatrix(31,17) = groebnerMatrix(13,54)/(groebnerMatrix(13,42)); groebnerMatrix(31,18) = groebnerMatrix(13,55)/(groebnerMatrix(13,42)); groebnerMatrix(31,19) = (groebnerMatrix(13,56)/(groebnerMatrix(13,42))-groebnerMatrix(14,57)/(groebnerMatrix(14,43))); groebnerMatrix(31,20) = groebnerMatrix(13,57)/(groebnerMatrix(13,42)); groebnerMatrix(31,23) = -groebnerMatrix(14,58)/(groebnerMatrix(14,43)); groebnerMatrix(31,24) = groebnerMatrix(13,58)/(groebnerMatrix(13,42)); groebnerMatrix(31,37) = -groebnerMatrix(14,65)/(groebnerMatrix(14,43)); groebnerMatrix(31,38) = -groebnerMatrix(14,66)/(groebnerMatrix(14,43)); groebnerMatrix(31,39) = -groebnerMatrix(14,67)/(groebnerMatrix(14,43)); groebnerMatrix(31,40) = groebnerMatrix(13,65)/(groebnerMatrix(13,42)); groebnerMatrix(31,41) = groebnerMatrix(13,66)/(groebnerMatrix(13,42)); groebnerMatrix(31,42) = (groebnerMatrix(13,67)/(groebnerMatrix(13,42))-groebnerMatrix(14,68)/(groebnerMatrix(14,43))); groebnerMatrix(31,43) = groebnerMatrix(13,68)/(groebnerMatrix(13,42)); groebnerMatrix(31,47) = -groebnerMatrix(14,69)/(groebnerMatrix(14,43)); groebnerMatrix(31,48) = -groebnerMatrix(14,70)/(groebnerMatrix(14,43)); groebnerMatrix(31,49) = -groebnerMatrix(14,71)/(groebnerMatrix(14,43)); groebnerMatrix(31,50) = groebnerMatrix(13,69)/(groebnerMatrix(13,42)); groebnerMatrix(31,51) = groebnerMatrix(13,70)/(groebnerMatrix(13,42)); groebnerMatrix(31,52) = (groebnerMatrix(13,71)/(groebnerMatrix(13,42))-groebnerMatrix(14,72)/(groebnerMatrix(14,43))); groebnerMatrix(31,53) = groebnerMatrix(13,72)/(groebnerMatrix(13,42)); groebnerMatrix(31,56) = -groebnerMatrix(14,73)/(groebnerMatrix(14,43)); groebnerMatrix(31,57) = groebnerMatrix(13,73)/(groebnerMatrix(13,42)); groebnerMatrix(31,62) = -groebnerMatrix(14,74)/(groebnerMatrix(14,43)); groebnerMatrix(31,63) = -groebnerMatrix(14,75)/(groebnerMatrix(14,43)); groebnerMatrix(31,64) = -groebnerMatrix(14,76)/(groebnerMatrix(14,43)); groebnerMatrix(31,65) = groebnerMatrix(13,74)/(groebnerMatrix(13,42)); groebnerMatrix(31,66) = groebnerMatrix(13,75)/(groebnerMatrix(13,42)); groebnerMatrix(31,67) = (groebnerMatrix(13,76)/(groebnerMatrix(13,42))-groebnerMatrix(14,77)/(groebnerMatrix(14,43))); groebnerMatrix(31,68) = groebnerMatrix(13,77)/(groebnerMatrix(13,42)); groebnerMatrix(31,71) = -groebnerMatrix(14,78)/(groebnerMatrix(14,43)); groebnerMatrix(31,72) = groebnerMatrix(13,78)/(groebnerMatrix(13,42)); groebnerMatrix(31,76) = -groebnerMatrix(14,79)/(groebnerMatrix(14,43)); groebnerMatrix(31,77) = groebnerMatrix(13,79)/(groebnerMatrix(13,42)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial32( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(32,0) = groebnerMatrix(12,42)/(groebnerMatrix(12,41)); groebnerMatrix(32,1) = groebnerMatrix(12,43)/(groebnerMatrix(12,41)); groebnerMatrix(32,2) = -groebnerMatrix(14,50)/(groebnerMatrix(14,43)); groebnerMatrix(32,3) = -groebnerMatrix(14,51)/(groebnerMatrix(14,43)); groebnerMatrix(32,5) = -groebnerMatrix(14,52)/(groebnerMatrix(14,43)); groebnerMatrix(32,7) = groebnerMatrix(12,50)/(groebnerMatrix(12,41)); groebnerMatrix(32,8) = (groebnerMatrix(12,51)/(groebnerMatrix(12,41))-groebnerMatrix(14,53)/(groebnerMatrix(14,43))); groebnerMatrix(32,9) = groebnerMatrix(12,52)/(groebnerMatrix(12,41)); groebnerMatrix(32,10) = groebnerMatrix(12,53)/(groebnerMatrix(12,41)); groebnerMatrix(32,12) = -groebnerMatrix(14,54)/(groebnerMatrix(14,43)); groebnerMatrix(32,13) = -groebnerMatrix(14,55)/(groebnerMatrix(14,43)); groebnerMatrix(32,15) = -groebnerMatrix(14,56)/(groebnerMatrix(14,43)); groebnerMatrix(32,17) = groebnerMatrix(12,54)/(groebnerMatrix(12,41)); groebnerMatrix(32,18) = (groebnerMatrix(12,55)/(groebnerMatrix(12,41))-groebnerMatrix(14,57)/(groebnerMatrix(14,43))); groebnerMatrix(32,19) = groebnerMatrix(12,56)/(groebnerMatrix(12,41)); groebnerMatrix(32,20) = groebnerMatrix(12,57)/(groebnerMatrix(12,41)); groebnerMatrix(32,22) = -groebnerMatrix(14,58)/(groebnerMatrix(14,43)); groebnerMatrix(32,24) = groebnerMatrix(12,58)/(groebnerMatrix(12,41)); groebnerMatrix(32,35) = -groebnerMatrix(14,65)/(groebnerMatrix(14,43)); groebnerMatrix(32,36) = -groebnerMatrix(14,66)/(groebnerMatrix(14,43)); groebnerMatrix(32,38) = -groebnerMatrix(14,67)/(groebnerMatrix(14,43)); groebnerMatrix(32,40) = groebnerMatrix(12,65)/(groebnerMatrix(12,41)); groebnerMatrix(32,41) = (groebnerMatrix(12,66)/(groebnerMatrix(12,41))-groebnerMatrix(14,68)/(groebnerMatrix(14,43))); groebnerMatrix(32,42) = groebnerMatrix(12,67)/(groebnerMatrix(12,41)); groebnerMatrix(32,43) = groebnerMatrix(12,68)/(groebnerMatrix(12,41)); groebnerMatrix(32,45) = -groebnerMatrix(14,69)/(groebnerMatrix(14,43)); groebnerMatrix(32,46) = -groebnerMatrix(14,70)/(groebnerMatrix(14,43)); groebnerMatrix(32,48) = -groebnerMatrix(14,71)/(groebnerMatrix(14,43)); groebnerMatrix(32,50) = groebnerMatrix(12,69)/(groebnerMatrix(12,41)); groebnerMatrix(32,51) = (groebnerMatrix(12,70)/(groebnerMatrix(12,41))-groebnerMatrix(14,72)/(groebnerMatrix(14,43))); groebnerMatrix(32,52) = groebnerMatrix(12,71)/(groebnerMatrix(12,41)); groebnerMatrix(32,53) = groebnerMatrix(12,72)/(groebnerMatrix(12,41)); groebnerMatrix(32,55) = -groebnerMatrix(14,73)/(groebnerMatrix(14,43)); groebnerMatrix(32,57) = groebnerMatrix(12,73)/(groebnerMatrix(12,41)); groebnerMatrix(32,60) = -groebnerMatrix(14,74)/(groebnerMatrix(14,43)); groebnerMatrix(32,61) = -groebnerMatrix(14,75)/(groebnerMatrix(14,43)); groebnerMatrix(32,63) = -groebnerMatrix(14,76)/(groebnerMatrix(14,43)); groebnerMatrix(32,65) = groebnerMatrix(12,74)/(groebnerMatrix(12,41)); groebnerMatrix(32,66) = (groebnerMatrix(12,75)/(groebnerMatrix(12,41))-groebnerMatrix(14,77)/(groebnerMatrix(14,43))); groebnerMatrix(32,67) = groebnerMatrix(12,76)/(groebnerMatrix(12,41)); groebnerMatrix(32,68) = groebnerMatrix(12,77)/(groebnerMatrix(12,41)); groebnerMatrix(32,70) = -groebnerMatrix(14,78)/(groebnerMatrix(14,43)); groebnerMatrix(32,72) = groebnerMatrix(12,78)/(groebnerMatrix(12,41)); groebnerMatrix(32,75) = -groebnerMatrix(14,79)/(groebnerMatrix(14,43)); groebnerMatrix(32,77) = groebnerMatrix(12,79)/(groebnerMatrix(12,41)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial33( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(33,54) = (groebnerMatrix(18,54)/(groebnerMatrix(18,53))-groebnerMatrix(32,69)/(groebnerMatrix(32,68))); groebnerMatrix(33,55) = (groebnerMatrix(18,55)/(groebnerMatrix(18,53))-groebnerMatrix(32,70)/(groebnerMatrix(32,68))); groebnerMatrix(33,56) = (groebnerMatrix(18,56)/(groebnerMatrix(18,53))-groebnerMatrix(32,71)/(groebnerMatrix(32,68))); groebnerMatrix(33,57) = (groebnerMatrix(18,57)/(groebnerMatrix(18,53))-groebnerMatrix(32,72)/(groebnerMatrix(32,68))); groebnerMatrix(33,58) = (groebnerMatrix(18,58)/(groebnerMatrix(18,53))-groebnerMatrix(32,73)/(groebnerMatrix(32,68))); groebnerMatrix(33,65) = groebnerMatrix(18,65)/(groebnerMatrix(18,53)); groebnerMatrix(33,66) = groebnerMatrix(18,66)/(groebnerMatrix(18,53)); groebnerMatrix(33,67) = groebnerMatrix(18,67)/(groebnerMatrix(18,53)); groebnerMatrix(33,68) = groebnerMatrix(18,68)/(groebnerMatrix(18,53)); groebnerMatrix(33,69) = (groebnerMatrix(18,69)/(groebnerMatrix(18,53))-groebnerMatrix(32,74)/(groebnerMatrix(32,68))); groebnerMatrix(33,70) = (groebnerMatrix(18,70)/(groebnerMatrix(18,53))-groebnerMatrix(32,75)/(groebnerMatrix(32,68))); groebnerMatrix(33,71) = (groebnerMatrix(18,71)/(groebnerMatrix(18,53))-groebnerMatrix(32,76)/(groebnerMatrix(32,68))); groebnerMatrix(33,72) = (groebnerMatrix(18,72)/(groebnerMatrix(18,53))-groebnerMatrix(32,77)/(groebnerMatrix(32,68))); groebnerMatrix(33,73) = (groebnerMatrix(18,73)/(groebnerMatrix(18,53))-groebnerMatrix(32,78)/(groebnerMatrix(32,68))); groebnerMatrix(33,74) = groebnerMatrix(18,74)/(groebnerMatrix(18,53)); groebnerMatrix(33,75) = groebnerMatrix(18,75)/(groebnerMatrix(18,53)); groebnerMatrix(33,76) = groebnerMatrix(18,76)/(groebnerMatrix(18,53)); groebnerMatrix(33,77) = groebnerMatrix(18,77)/(groebnerMatrix(18,53)); groebnerMatrix(33,78) = (groebnerMatrix(18,78)/(groebnerMatrix(18,53))-groebnerMatrix(32,79)/(groebnerMatrix(32,68))); groebnerMatrix(33,79) = groebnerMatrix(18,79)/(groebnerMatrix(18,53)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial34( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(34,53) = (groebnerMatrix(17,53)/(groebnerMatrix(17,52))-groebnerMatrix(31,68)/(groebnerMatrix(31,67))); groebnerMatrix(34,54) = (groebnerMatrix(17,54)/(groebnerMatrix(17,52))-groebnerMatrix(31,69)/(groebnerMatrix(31,67))); groebnerMatrix(34,55) = (groebnerMatrix(17,55)/(groebnerMatrix(17,52))-groebnerMatrix(31,70)/(groebnerMatrix(31,67))); groebnerMatrix(34,56) = (groebnerMatrix(17,56)/(groebnerMatrix(17,52))-groebnerMatrix(31,71)/(groebnerMatrix(31,67))); groebnerMatrix(34,57) = (groebnerMatrix(17,57)/(groebnerMatrix(17,52))-groebnerMatrix(31,72)/(groebnerMatrix(31,67))); groebnerMatrix(34,58) = (groebnerMatrix(17,58)/(groebnerMatrix(17,52))-groebnerMatrix(31,73)/(groebnerMatrix(31,67))); groebnerMatrix(34,65) = groebnerMatrix(17,65)/(groebnerMatrix(17,52)); groebnerMatrix(34,66) = groebnerMatrix(17,66)/(groebnerMatrix(17,52)); groebnerMatrix(34,67) = groebnerMatrix(17,67)/(groebnerMatrix(17,52)); groebnerMatrix(34,68) = groebnerMatrix(17,68)/(groebnerMatrix(17,52)); groebnerMatrix(34,69) = (groebnerMatrix(17,69)/(groebnerMatrix(17,52))-groebnerMatrix(31,74)/(groebnerMatrix(31,67))); groebnerMatrix(34,70) = (groebnerMatrix(17,70)/(groebnerMatrix(17,52))-groebnerMatrix(31,75)/(groebnerMatrix(31,67))); groebnerMatrix(34,71) = (groebnerMatrix(17,71)/(groebnerMatrix(17,52))-groebnerMatrix(31,76)/(groebnerMatrix(31,67))); groebnerMatrix(34,72) = (groebnerMatrix(17,72)/(groebnerMatrix(17,52))-groebnerMatrix(31,77)/(groebnerMatrix(31,67))); groebnerMatrix(34,73) = (groebnerMatrix(17,73)/(groebnerMatrix(17,52))-groebnerMatrix(31,78)/(groebnerMatrix(31,67))); groebnerMatrix(34,74) = groebnerMatrix(17,74)/(groebnerMatrix(17,52)); groebnerMatrix(34,75) = groebnerMatrix(17,75)/(groebnerMatrix(17,52)); groebnerMatrix(34,76) = groebnerMatrix(17,76)/(groebnerMatrix(17,52)); groebnerMatrix(34,77) = groebnerMatrix(17,77)/(groebnerMatrix(17,52)); groebnerMatrix(34,78) = (groebnerMatrix(17,78)/(groebnerMatrix(17,52))-groebnerMatrix(31,79)/(groebnerMatrix(31,67))); groebnerMatrix(34,79) = groebnerMatrix(17,79)/(groebnerMatrix(17,52)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial35( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(35,52) = (groebnerMatrix(16,52)/(groebnerMatrix(16,51))-groebnerMatrix(30,67)/(groebnerMatrix(30,66))); groebnerMatrix(35,53) = (groebnerMatrix(16,53)/(groebnerMatrix(16,51))-groebnerMatrix(30,68)/(groebnerMatrix(30,66))); groebnerMatrix(35,54) = (groebnerMatrix(16,54)/(groebnerMatrix(16,51))-groebnerMatrix(30,69)/(groebnerMatrix(30,66))); groebnerMatrix(35,55) = (groebnerMatrix(16,55)/(groebnerMatrix(16,51))-groebnerMatrix(30,70)/(groebnerMatrix(30,66))); groebnerMatrix(35,56) = (groebnerMatrix(16,56)/(groebnerMatrix(16,51))-groebnerMatrix(30,71)/(groebnerMatrix(30,66))); groebnerMatrix(35,57) = (groebnerMatrix(16,57)/(groebnerMatrix(16,51))-groebnerMatrix(30,72)/(groebnerMatrix(30,66))); groebnerMatrix(35,58) = (groebnerMatrix(16,58)/(groebnerMatrix(16,51))-groebnerMatrix(30,73)/(groebnerMatrix(30,66))); groebnerMatrix(35,65) = groebnerMatrix(16,65)/(groebnerMatrix(16,51)); groebnerMatrix(35,66) = groebnerMatrix(16,66)/(groebnerMatrix(16,51)); groebnerMatrix(35,67) = groebnerMatrix(16,67)/(groebnerMatrix(16,51)); groebnerMatrix(35,68) = groebnerMatrix(16,68)/(groebnerMatrix(16,51)); groebnerMatrix(35,69) = (groebnerMatrix(16,69)/(groebnerMatrix(16,51))-groebnerMatrix(30,74)/(groebnerMatrix(30,66))); groebnerMatrix(35,70) = (groebnerMatrix(16,70)/(groebnerMatrix(16,51))-groebnerMatrix(30,75)/(groebnerMatrix(30,66))); groebnerMatrix(35,71) = (groebnerMatrix(16,71)/(groebnerMatrix(16,51))-groebnerMatrix(30,76)/(groebnerMatrix(30,66))); groebnerMatrix(35,72) = (groebnerMatrix(16,72)/(groebnerMatrix(16,51))-groebnerMatrix(30,77)/(groebnerMatrix(30,66))); groebnerMatrix(35,73) = (groebnerMatrix(16,73)/(groebnerMatrix(16,51))-groebnerMatrix(30,78)/(groebnerMatrix(30,66))); groebnerMatrix(35,74) = groebnerMatrix(16,74)/(groebnerMatrix(16,51)); groebnerMatrix(35,75) = groebnerMatrix(16,75)/(groebnerMatrix(16,51)); groebnerMatrix(35,76) = groebnerMatrix(16,76)/(groebnerMatrix(16,51)); groebnerMatrix(35,77) = groebnerMatrix(16,77)/(groebnerMatrix(16,51)); groebnerMatrix(35,78) = (groebnerMatrix(16,78)/(groebnerMatrix(16,51))-groebnerMatrix(30,79)/(groebnerMatrix(30,66))); groebnerMatrix(35,79) = groebnerMatrix(16,79)/(groebnerMatrix(16,51)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial36( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(36,51) = (groebnerMatrix(15,51)/(groebnerMatrix(15,50))-groebnerMatrix(29,66)/(groebnerMatrix(29,65))); groebnerMatrix(36,52) = (groebnerMatrix(15,52)/(groebnerMatrix(15,50))-groebnerMatrix(29,67)/(groebnerMatrix(29,65))); groebnerMatrix(36,53) = (groebnerMatrix(15,53)/(groebnerMatrix(15,50))-groebnerMatrix(29,68)/(groebnerMatrix(29,65))); groebnerMatrix(36,54) = (groebnerMatrix(15,54)/(groebnerMatrix(15,50))-groebnerMatrix(29,69)/(groebnerMatrix(29,65))); groebnerMatrix(36,55) = (groebnerMatrix(15,55)/(groebnerMatrix(15,50))-groebnerMatrix(29,70)/(groebnerMatrix(29,65))); groebnerMatrix(36,56) = (groebnerMatrix(15,56)/(groebnerMatrix(15,50))-groebnerMatrix(29,71)/(groebnerMatrix(29,65))); groebnerMatrix(36,57) = (groebnerMatrix(15,57)/(groebnerMatrix(15,50))-groebnerMatrix(29,72)/(groebnerMatrix(29,65))); groebnerMatrix(36,58) = (groebnerMatrix(15,58)/(groebnerMatrix(15,50))-groebnerMatrix(29,73)/(groebnerMatrix(29,65))); groebnerMatrix(36,65) = groebnerMatrix(15,65)/(groebnerMatrix(15,50)); groebnerMatrix(36,66) = groebnerMatrix(15,66)/(groebnerMatrix(15,50)); groebnerMatrix(36,67) = groebnerMatrix(15,67)/(groebnerMatrix(15,50)); groebnerMatrix(36,68) = groebnerMatrix(15,68)/(groebnerMatrix(15,50)); groebnerMatrix(36,69) = (groebnerMatrix(15,69)/(groebnerMatrix(15,50))-groebnerMatrix(29,74)/(groebnerMatrix(29,65))); groebnerMatrix(36,70) = (groebnerMatrix(15,70)/(groebnerMatrix(15,50))-groebnerMatrix(29,75)/(groebnerMatrix(29,65))); groebnerMatrix(36,71) = (groebnerMatrix(15,71)/(groebnerMatrix(15,50))-groebnerMatrix(29,76)/(groebnerMatrix(29,65))); groebnerMatrix(36,72) = (groebnerMatrix(15,72)/(groebnerMatrix(15,50))-groebnerMatrix(29,77)/(groebnerMatrix(29,65))); groebnerMatrix(36,73) = (groebnerMatrix(15,73)/(groebnerMatrix(15,50))-groebnerMatrix(29,78)/(groebnerMatrix(29,65))); groebnerMatrix(36,74) = groebnerMatrix(15,74)/(groebnerMatrix(15,50)); groebnerMatrix(36,75) = groebnerMatrix(15,75)/(groebnerMatrix(15,50)); groebnerMatrix(36,76) = groebnerMatrix(15,76)/(groebnerMatrix(15,50)); groebnerMatrix(36,77) = groebnerMatrix(15,77)/(groebnerMatrix(15,50)); groebnerMatrix(36,78) = (groebnerMatrix(15,78)/(groebnerMatrix(15,50))-groebnerMatrix(29,79)/(groebnerMatrix(29,65))); groebnerMatrix(36,79) = groebnerMatrix(15,79)/(groebnerMatrix(15,50)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial37( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(37,50) = (groebnerMatrix(14,50)/(groebnerMatrix(14,43))-groebnerMatrix(32,69)/(groebnerMatrix(32,68))); groebnerMatrix(37,51) = (groebnerMatrix(14,51)/(groebnerMatrix(14,43))-groebnerMatrix(32,70)/(groebnerMatrix(32,68))); groebnerMatrix(37,52) = (groebnerMatrix(14,52)/(groebnerMatrix(14,43))-groebnerMatrix(32,71)/(groebnerMatrix(32,68))); groebnerMatrix(37,53) = (groebnerMatrix(14,53)/(groebnerMatrix(14,43))-groebnerMatrix(32,72)/(groebnerMatrix(32,68))); groebnerMatrix(37,54) = groebnerMatrix(14,54)/(groebnerMatrix(14,43)); groebnerMatrix(37,55) = groebnerMatrix(14,55)/(groebnerMatrix(14,43)); groebnerMatrix(37,56) = groebnerMatrix(14,56)/(groebnerMatrix(14,43)); groebnerMatrix(37,57) = (groebnerMatrix(14,57)/(groebnerMatrix(14,43))-groebnerMatrix(32,73)/(groebnerMatrix(32,68))); groebnerMatrix(37,58) = groebnerMatrix(14,58)/(groebnerMatrix(14,43)); groebnerMatrix(37,65) = (groebnerMatrix(14,65)/(groebnerMatrix(14,43))-groebnerMatrix(32,74)/(groebnerMatrix(32,68))); groebnerMatrix(37,66) = (groebnerMatrix(14,66)/(groebnerMatrix(14,43))-groebnerMatrix(32,75)/(groebnerMatrix(32,68))); groebnerMatrix(37,67) = (groebnerMatrix(14,67)/(groebnerMatrix(14,43))-groebnerMatrix(32,76)/(groebnerMatrix(32,68))); groebnerMatrix(37,68) = (groebnerMatrix(14,68)/(groebnerMatrix(14,43))-groebnerMatrix(32,77)/(groebnerMatrix(32,68))); groebnerMatrix(37,69) = groebnerMatrix(14,69)/(groebnerMatrix(14,43)); groebnerMatrix(37,70) = groebnerMatrix(14,70)/(groebnerMatrix(14,43)); groebnerMatrix(37,71) = groebnerMatrix(14,71)/(groebnerMatrix(14,43)); groebnerMatrix(37,72) = (groebnerMatrix(14,72)/(groebnerMatrix(14,43))-groebnerMatrix(32,78)/(groebnerMatrix(32,68))); groebnerMatrix(37,73) = groebnerMatrix(14,73)/(groebnerMatrix(14,43)); groebnerMatrix(37,74) = groebnerMatrix(14,74)/(groebnerMatrix(14,43)); groebnerMatrix(37,75) = groebnerMatrix(14,75)/(groebnerMatrix(14,43)); groebnerMatrix(37,76) = groebnerMatrix(14,76)/(groebnerMatrix(14,43)); groebnerMatrix(37,77) = (groebnerMatrix(14,77)/(groebnerMatrix(14,43))-groebnerMatrix(32,79)/(groebnerMatrix(32,68))); groebnerMatrix(37,78) = groebnerMatrix(14,78)/(groebnerMatrix(14,43)); groebnerMatrix(37,79) = groebnerMatrix(14,79)/(groebnerMatrix(14,43)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial38( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(38,43) = (groebnerMatrix(13,43)/(groebnerMatrix(13,42))-groebnerMatrix(31,68)/(groebnerMatrix(31,67))); groebnerMatrix(38,50) = (groebnerMatrix(13,50)/(groebnerMatrix(13,42))-groebnerMatrix(31,69)/(groebnerMatrix(31,67))); groebnerMatrix(38,51) = (groebnerMatrix(13,51)/(groebnerMatrix(13,42))-groebnerMatrix(31,70)/(groebnerMatrix(31,67))); groebnerMatrix(38,52) = (groebnerMatrix(13,52)/(groebnerMatrix(13,42))-groebnerMatrix(31,71)/(groebnerMatrix(31,67))); groebnerMatrix(38,53) = (groebnerMatrix(13,53)/(groebnerMatrix(13,42))-groebnerMatrix(31,72)/(groebnerMatrix(31,67))); groebnerMatrix(38,54) = groebnerMatrix(13,54)/(groebnerMatrix(13,42)); groebnerMatrix(38,55) = groebnerMatrix(13,55)/(groebnerMatrix(13,42)); groebnerMatrix(38,56) = groebnerMatrix(13,56)/(groebnerMatrix(13,42)); groebnerMatrix(38,57) = (groebnerMatrix(13,57)/(groebnerMatrix(13,42))-groebnerMatrix(31,73)/(groebnerMatrix(31,67))); groebnerMatrix(38,58) = groebnerMatrix(13,58)/(groebnerMatrix(13,42)); groebnerMatrix(38,65) = (groebnerMatrix(13,65)/(groebnerMatrix(13,42))-groebnerMatrix(31,74)/(groebnerMatrix(31,67))); groebnerMatrix(38,66) = (groebnerMatrix(13,66)/(groebnerMatrix(13,42))-groebnerMatrix(31,75)/(groebnerMatrix(31,67))); groebnerMatrix(38,67) = (groebnerMatrix(13,67)/(groebnerMatrix(13,42))-groebnerMatrix(31,76)/(groebnerMatrix(31,67))); groebnerMatrix(38,68) = (groebnerMatrix(13,68)/(groebnerMatrix(13,42))-groebnerMatrix(31,77)/(groebnerMatrix(31,67))); groebnerMatrix(38,69) = groebnerMatrix(13,69)/(groebnerMatrix(13,42)); groebnerMatrix(38,70) = groebnerMatrix(13,70)/(groebnerMatrix(13,42)); groebnerMatrix(38,71) = groebnerMatrix(13,71)/(groebnerMatrix(13,42)); groebnerMatrix(38,72) = (groebnerMatrix(13,72)/(groebnerMatrix(13,42))-groebnerMatrix(31,78)/(groebnerMatrix(31,67))); groebnerMatrix(38,73) = groebnerMatrix(13,73)/(groebnerMatrix(13,42)); groebnerMatrix(38,74) = groebnerMatrix(13,74)/(groebnerMatrix(13,42)); groebnerMatrix(38,75) = groebnerMatrix(13,75)/(groebnerMatrix(13,42)); groebnerMatrix(38,76) = groebnerMatrix(13,76)/(groebnerMatrix(13,42)); groebnerMatrix(38,77) = (groebnerMatrix(13,77)/(groebnerMatrix(13,42))-groebnerMatrix(31,79)/(groebnerMatrix(31,67))); groebnerMatrix(38,78) = groebnerMatrix(13,78)/(groebnerMatrix(13,42)); groebnerMatrix(38,79) = groebnerMatrix(13,79)/(groebnerMatrix(13,42)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial39( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(39,43) = groebnerMatrix(31,68)/(groebnerMatrix(31,67)); groebnerMatrix(39,47) = -groebnerMatrix(32,69)/(groebnerMatrix(32,68)); groebnerMatrix(39,48) = -groebnerMatrix(32,70)/(groebnerMatrix(32,68)); groebnerMatrix(39,49) = -groebnerMatrix(32,71)/(groebnerMatrix(32,68)); groebnerMatrix(39,50) = groebnerMatrix(31,69)/(groebnerMatrix(31,67)); groebnerMatrix(39,51) = groebnerMatrix(31,70)/(groebnerMatrix(31,67)); groebnerMatrix(39,52) = (groebnerMatrix(31,71)/(groebnerMatrix(31,67))-groebnerMatrix(32,72)/(groebnerMatrix(32,68))); groebnerMatrix(39,53) = groebnerMatrix(31,72)/(groebnerMatrix(31,67)); groebnerMatrix(39,56) = -groebnerMatrix(32,73)/(groebnerMatrix(32,68)); groebnerMatrix(39,57) = groebnerMatrix(31,73)/(groebnerMatrix(31,67)); groebnerMatrix(39,62) = -groebnerMatrix(32,74)/(groebnerMatrix(32,68)); groebnerMatrix(39,63) = -groebnerMatrix(32,75)/(groebnerMatrix(32,68)); groebnerMatrix(39,64) = -groebnerMatrix(32,76)/(groebnerMatrix(32,68)); groebnerMatrix(39,65) = groebnerMatrix(31,74)/(groebnerMatrix(31,67)); groebnerMatrix(39,66) = groebnerMatrix(31,75)/(groebnerMatrix(31,67)); groebnerMatrix(39,67) = (groebnerMatrix(31,76)/(groebnerMatrix(31,67))-groebnerMatrix(32,77)/(groebnerMatrix(32,68))); groebnerMatrix(39,68) = groebnerMatrix(31,77)/(groebnerMatrix(31,67)); groebnerMatrix(39,71) = -groebnerMatrix(32,78)/(groebnerMatrix(32,68)); groebnerMatrix(39,72) = groebnerMatrix(31,78)/(groebnerMatrix(31,67)); groebnerMatrix(39,76) = -groebnerMatrix(32,79)/(groebnerMatrix(32,68)); groebnerMatrix(39,77) = groebnerMatrix(31,79)/(groebnerMatrix(31,67)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial40( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(40,42) = (groebnerMatrix(12,42)/(groebnerMatrix(12,41))-groebnerMatrix(30,67)/(groebnerMatrix(30,66))); groebnerMatrix(40,43) = (groebnerMatrix(12,43)/(groebnerMatrix(12,41))-groebnerMatrix(30,68)/(groebnerMatrix(30,66))); groebnerMatrix(40,50) = (groebnerMatrix(12,50)/(groebnerMatrix(12,41))-groebnerMatrix(30,69)/(groebnerMatrix(30,66))); groebnerMatrix(40,51) = (groebnerMatrix(12,51)/(groebnerMatrix(12,41))-groebnerMatrix(30,70)/(groebnerMatrix(30,66))); groebnerMatrix(40,52) = (groebnerMatrix(12,52)/(groebnerMatrix(12,41))-groebnerMatrix(30,71)/(groebnerMatrix(30,66))); groebnerMatrix(40,53) = (groebnerMatrix(12,53)/(groebnerMatrix(12,41))-groebnerMatrix(30,72)/(groebnerMatrix(30,66))); groebnerMatrix(40,54) = groebnerMatrix(12,54)/(groebnerMatrix(12,41)); groebnerMatrix(40,55) = groebnerMatrix(12,55)/(groebnerMatrix(12,41)); groebnerMatrix(40,56) = groebnerMatrix(12,56)/(groebnerMatrix(12,41)); groebnerMatrix(40,57) = (groebnerMatrix(12,57)/(groebnerMatrix(12,41))-groebnerMatrix(30,73)/(groebnerMatrix(30,66))); groebnerMatrix(40,58) = groebnerMatrix(12,58)/(groebnerMatrix(12,41)); groebnerMatrix(40,65) = (groebnerMatrix(12,65)/(groebnerMatrix(12,41))-groebnerMatrix(30,74)/(groebnerMatrix(30,66))); groebnerMatrix(40,66) = (groebnerMatrix(12,66)/(groebnerMatrix(12,41))-groebnerMatrix(30,75)/(groebnerMatrix(30,66))); groebnerMatrix(40,67) = (groebnerMatrix(12,67)/(groebnerMatrix(12,41))-groebnerMatrix(30,76)/(groebnerMatrix(30,66))); groebnerMatrix(40,68) = (groebnerMatrix(12,68)/(groebnerMatrix(12,41))-groebnerMatrix(30,77)/(groebnerMatrix(30,66))); groebnerMatrix(40,69) = groebnerMatrix(12,69)/(groebnerMatrix(12,41)); groebnerMatrix(40,70) = groebnerMatrix(12,70)/(groebnerMatrix(12,41)); groebnerMatrix(40,71) = groebnerMatrix(12,71)/(groebnerMatrix(12,41)); groebnerMatrix(40,72) = (groebnerMatrix(12,72)/(groebnerMatrix(12,41))-groebnerMatrix(30,78)/(groebnerMatrix(30,66))); groebnerMatrix(40,73) = groebnerMatrix(12,73)/(groebnerMatrix(12,41)); groebnerMatrix(40,74) = groebnerMatrix(12,74)/(groebnerMatrix(12,41)); groebnerMatrix(40,75) = groebnerMatrix(12,75)/(groebnerMatrix(12,41)); groebnerMatrix(40,76) = groebnerMatrix(12,76)/(groebnerMatrix(12,41)); groebnerMatrix(40,77) = (groebnerMatrix(12,77)/(groebnerMatrix(12,41))-groebnerMatrix(30,79)/(groebnerMatrix(30,66))); groebnerMatrix(40,78) = groebnerMatrix(12,78)/(groebnerMatrix(12,41)); groebnerMatrix(40,79) = groebnerMatrix(12,79)/(groebnerMatrix(12,41)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial41( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(41,42) = groebnerMatrix(30,67)/(groebnerMatrix(30,66)); groebnerMatrix(41,43) = groebnerMatrix(30,68)/(groebnerMatrix(30,66)); groebnerMatrix(41,45) = -groebnerMatrix(32,69)/(groebnerMatrix(32,68)); groebnerMatrix(41,46) = -groebnerMatrix(32,70)/(groebnerMatrix(32,68)); groebnerMatrix(41,48) = -groebnerMatrix(32,71)/(groebnerMatrix(32,68)); groebnerMatrix(41,50) = groebnerMatrix(30,69)/(groebnerMatrix(30,66)); groebnerMatrix(41,51) = (groebnerMatrix(30,70)/(groebnerMatrix(30,66))-groebnerMatrix(32,72)/(groebnerMatrix(32,68))); groebnerMatrix(41,52) = groebnerMatrix(30,71)/(groebnerMatrix(30,66)); groebnerMatrix(41,53) = groebnerMatrix(30,72)/(groebnerMatrix(30,66)); groebnerMatrix(41,55) = -groebnerMatrix(32,73)/(groebnerMatrix(32,68)); groebnerMatrix(41,57) = groebnerMatrix(30,73)/(groebnerMatrix(30,66)); groebnerMatrix(41,60) = -groebnerMatrix(32,74)/(groebnerMatrix(32,68)); groebnerMatrix(41,61) = -groebnerMatrix(32,75)/(groebnerMatrix(32,68)); groebnerMatrix(41,63) = -groebnerMatrix(32,76)/(groebnerMatrix(32,68)); groebnerMatrix(41,65) = groebnerMatrix(30,74)/(groebnerMatrix(30,66)); groebnerMatrix(41,66) = (groebnerMatrix(30,75)/(groebnerMatrix(30,66))-groebnerMatrix(32,77)/(groebnerMatrix(32,68))); groebnerMatrix(41,67) = groebnerMatrix(30,76)/(groebnerMatrix(30,66)); groebnerMatrix(41,68) = groebnerMatrix(30,77)/(groebnerMatrix(30,66)); groebnerMatrix(41,70) = -groebnerMatrix(32,78)/(groebnerMatrix(32,68)); groebnerMatrix(41,72) = groebnerMatrix(30,78)/(groebnerMatrix(30,66)); groebnerMatrix(41,75) = -groebnerMatrix(32,79)/(groebnerMatrix(32,68)); groebnerMatrix(41,77) = groebnerMatrix(30,79)/(groebnerMatrix(30,66)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial42( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(42,41) = (groebnerMatrix(11,41)/(groebnerMatrix(11,40))-groebnerMatrix(29,66)/(groebnerMatrix(29,65))); groebnerMatrix(42,42) = (groebnerMatrix(11,42)/(groebnerMatrix(11,40))-groebnerMatrix(29,67)/(groebnerMatrix(29,65))); groebnerMatrix(42,43) = (groebnerMatrix(11,43)/(groebnerMatrix(11,40))-groebnerMatrix(29,68)/(groebnerMatrix(29,65))); groebnerMatrix(42,50) = (groebnerMatrix(11,50)/(groebnerMatrix(11,40))-groebnerMatrix(29,69)/(groebnerMatrix(29,65))); groebnerMatrix(42,51) = (groebnerMatrix(11,51)/(groebnerMatrix(11,40))-groebnerMatrix(29,70)/(groebnerMatrix(29,65))); groebnerMatrix(42,52) = (groebnerMatrix(11,52)/(groebnerMatrix(11,40))-groebnerMatrix(29,71)/(groebnerMatrix(29,65))); groebnerMatrix(42,53) = (groebnerMatrix(11,53)/(groebnerMatrix(11,40))-groebnerMatrix(29,72)/(groebnerMatrix(29,65))); groebnerMatrix(42,54) = groebnerMatrix(11,54)/(groebnerMatrix(11,40)); groebnerMatrix(42,55) = groebnerMatrix(11,55)/(groebnerMatrix(11,40)); groebnerMatrix(42,56) = groebnerMatrix(11,56)/(groebnerMatrix(11,40)); groebnerMatrix(42,57) = (groebnerMatrix(11,57)/(groebnerMatrix(11,40))-groebnerMatrix(29,73)/(groebnerMatrix(29,65))); groebnerMatrix(42,58) = groebnerMatrix(11,58)/(groebnerMatrix(11,40)); groebnerMatrix(42,65) = (groebnerMatrix(11,65)/(groebnerMatrix(11,40))-groebnerMatrix(29,74)/(groebnerMatrix(29,65))); groebnerMatrix(42,66) = (groebnerMatrix(11,66)/(groebnerMatrix(11,40))-groebnerMatrix(29,75)/(groebnerMatrix(29,65))); groebnerMatrix(42,67) = (groebnerMatrix(11,67)/(groebnerMatrix(11,40))-groebnerMatrix(29,76)/(groebnerMatrix(29,65))); groebnerMatrix(42,68) = (groebnerMatrix(11,68)/(groebnerMatrix(11,40))-groebnerMatrix(29,77)/(groebnerMatrix(29,65))); groebnerMatrix(42,69) = groebnerMatrix(11,69)/(groebnerMatrix(11,40)); groebnerMatrix(42,70) = groebnerMatrix(11,70)/(groebnerMatrix(11,40)); groebnerMatrix(42,71) = groebnerMatrix(11,71)/(groebnerMatrix(11,40)); groebnerMatrix(42,72) = (groebnerMatrix(11,72)/(groebnerMatrix(11,40))-groebnerMatrix(29,78)/(groebnerMatrix(29,65))); groebnerMatrix(42,73) = groebnerMatrix(11,73)/(groebnerMatrix(11,40)); groebnerMatrix(42,74) = groebnerMatrix(11,74)/(groebnerMatrix(11,40)); groebnerMatrix(42,75) = groebnerMatrix(11,75)/(groebnerMatrix(11,40)); groebnerMatrix(42,76) = groebnerMatrix(11,76)/(groebnerMatrix(11,40)); groebnerMatrix(42,77) = (groebnerMatrix(11,77)/(groebnerMatrix(11,40))-groebnerMatrix(29,79)/(groebnerMatrix(29,65))); groebnerMatrix(42,78) = groebnerMatrix(11,78)/(groebnerMatrix(11,40)); groebnerMatrix(42,79) = groebnerMatrix(11,79)/(groebnerMatrix(11,40)); } void opengv::absolute_pose::modules::gpnp5::sPolynomial43( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(43,50) = -groebnerMatrix(28,65)/(groebnerMatrix(28,58)); groebnerMatrix(43,51) = -groebnerMatrix(28,66)/(groebnerMatrix(28,58)); groebnerMatrix(43,52) = -groebnerMatrix(28,67)/(groebnerMatrix(28,58)); groebnerMatrix(43,53) = -groebnerMatrix(28,68)/(groebnerMatrix(28,58)); groebnerMatrix(43,54) = (groebnerMatrix(23,54)/(groebnerMatrix(23,25))-groebnerMatrix(28,69)/(groebnerMatrix(28,58))); groebnerMatrix(43,55) = (groebnerMatrix(23,55)/(groebnerMatrix(23,25))-groebnerMatrix(28,70)/(groebnerMatrix(28,58))); groebnerMatrix(43,56) = (groebnerMatrix(23,56)/(groebnerMatrix(23,25))-groebnerMatrix(28,71)/(groebnerMatrix(28,58))); groebnerMatrix(43,57) = (groebnerMatrix(23,57)/(groebnerMatrix(23,25))-groebnerMatrix(28,72)/(groebnerMatrix(28,58))); groebnerMatrix(43,58) = (groebnerMatrix(23,58)/(groebnerMatrix(23,25))-groebnerMatrix(28,73)/(groebnerMatrix(28,58))); groebnerMatrix(43,65) = groebnerMatrix(23,65)/(groebnerMatrix(23,25)); groebnerMatrix(43,66) = groebnerMatrix(23,66)/(groebnerMatrix(23,25)); groebnerMatrix(43,67) = groebnerMatrix(23,67)/(groebnerMatrix(23,25)); groebnerMatrix(43,68) = groebnerMatrix(23,68)/(groebnerMatrix(23,25)); groebnerMatrix(43,69) = (groebnerMatrix(23,69)/(groebnerMatrix(23,25))-groebnerMatrix(28,74)/(groebnerMatrix(28,58))); groebnerMatrix(43,70) = (groebnerMatrix(23,70)/(groebnerMatrix(23,25))-groebnerMatrix(28,75)/(groebnerMatrix(28,58))); groebnerMatrix(43,71) = (groebnerMatrix(23,71)/(groebnerMatrix(23,25))-groebnerMatrix(28,76)/(groebnerMatrix(28,58))); groebnerMatrix(43,72) = (groebnerMatrix(23,72)/(groebnerMatrix(23,25))-groebnerMatrix(28,77)/(groebnerMatrix(28,58))); groebnerMatrix(43,73) = (groebnerMatrix(23,73)/(groebnerMatrix(23,25))-groebnerMatrix(28,78)/(groebnerMatrix(28,58))); groebnerMatrix(43,74) = groebnerMatrix(23,74)/(groebnerMatrix(23,25)); groebnerMatrix(43,75) = groebnerMatrix(23,75)/(groebnerMatrix(23,25)); groebnerMatrix(43,76) = groebnerMatrix(23,76)/(groebnerMatrix(23,25)); groebnerMatrix(43,77) = groebnerMatrix(23,77)/(groebnerMatrix(23,25)); groebnerMatrix(43,78) = (groebnerMatrix(23,78)/(groebnerMatrix(23,25))-groebnerMatrix(28,79)/(groebnerMatrix(28,58))); groebnerMatrix(43,79) = groebnerMatrix(23,79)/(groebnerMatrix(23,25)); } opengv/src/absolute_pose/modules/gpnp5/init.cpp0000664016516101651610000007546413344612246020632 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp5::init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Matrix & k, Eigen::Matrix & l, Eigen::Matrix & p, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ) { Eigen::Vector3d temp = c0-c1; double c01w = temp.norm()*temp.norm(); temp = c0-c2; double c02w = temp.norm()*temp.norm(); temp = c0-c3; double c03w = temp.norm()*temp.norm(); temp = c1-c2; double c12w = temp.norm()*temp.norm(); temp = c1-c3; double c13w = temp.norm()*temp.norm(); temp = c2-c3; double c23w = temp.norm()*temp.norm(); groebnerMatrix(0,59) = ((((((((-2*p(0,0)*p(3,0)+pow(p(1,0),2))+pow(p(4,0),2))+pow(p(2,0),2))+pow(p(5,0),2))+pow(p(0,0),2))+pow(p(3,0),2))-2*p(1,0)*p(4,0))-2*p(2,0)*p(5,0)); groebnerMatrix(0,60) = (((((((((((2*l(1,0)*p(1,0)-2*l(1,0)*p(4,0))-2*p(1,0)*l(4,0))+2*l(4,0)*p(4,0))+2*l(2,0)*p(2,0))-2*l(2,0)*p(5,0))-2*p(2,0)*l(5,0))+2*l(5,0)*p(5,0))+2*l(0,0)*p(0,0))-2*l(0,0)*p(3,0))-2*p(0,0)*l(3,0))+2*l(3,0)*p(3,0)); groebnerMatrix(0,61) = ((((((((-2*l(0,0)*l(3,0)+pow(l(1,0),2))+pow(l(4,0),2))+pow(l(2,0),2))+pow(l(5,0),2))+pow(l(0,0),2))+pow(l(3,0),2))-2*l(1,0)*l(4,0))-2*l(2,0)*l(5,0)); groebnerMatrix(0,62) = (((((((((((2*k(1,0)*p(1,0)-2*k(1,0)*p(4,0))-2*p(1,0)*k(4,0))+2*k(4,0)*p(4,0))+2*k(2,0)*p(2,0))-2*k(2,0)*p(5,0))-2*p(2,0)*k(5,0))+2*k(5,0)*p(5,0))+2*k(0,0)*p(0,0))-2*k(0,0)*p(3,0))-2*p(0,0)*k(3,0))+2*k(3,0)*p(3,0)); groebnerMatrix(0,63) = (((((((((((2*k(1,0)*l(1,0)-2*k(1,0)*l(4,0))-2*l(1,0)*k(4,0))+2*k(4,0)*l(4,0))+2*k(2,0)*l(2,0))-2*k(2,0)*l(5,0))-2*l(2,0)*k(5,0))+2*k(5,0)*l(5,0))+2*k(0,0)*l(0,0))-2*k(0,0)*l(3,0))-2*l(0,0)*k(3,0))+2*k(3,0)*l(3,0)); groebnerMatrix(0,64) = ((((((((-2*k(0,0)*k(3,0)+pow(k(1,0),2))+pow(k(4,0),2))+pow(k(2,0),2))+pow(k(5,0),2))+pow(k(0,0),2))+pow(k(3,0),2))-2*k(1,0)*k(4,0))-2*k(2,0)*k(5,0)); groebnerMatrix(0,65) = (((((((((((2*m(1,0)*p(1,0)-2*m(1,0)*p(4,0))-2*p(1,0)*m(4,0))+2*m(4,0)*p(4,0))+2*m(2,0)*p(2,0))-2*m(2,0)*p(5,0))-2*p(2,0)*m(5,0))+2*m(5,0)*p(5,0))+2*m(0,0)*p(0,0))-2*m(0,0)*p(3,0))-2*p(0,0)*m(3,0))+2*m(3,0)*p(3,0)); groebnerMatrix(0,66) = (((((((((((2*m(1,0)*l(1,0)-2*m(1,0)*l(4,0))-2*l(1,0)*m(4,0))+2*m(4,0)*l(4,0))+2*m(2,0)*l(2,0))-2*m(2,0)*l(5,0))-2*l(2,0)*m(5,0))+2*m(5,0)*l(5,0))+2*m(0,0)*l(0,0))-2*m(0,0)*l(3,0))-2*l(0,0)*m(3,0))+2*m(3,0)*l(3,0)); groebnerMatrix(0,67) = (((((((((((2*m(1,0)*k(1,0)-2*m(1,0)*k(4,0))-2*k(1,0)*m(4,0))+2*m(4,0)*k(4,0))+2*m(2,0)*k(2,0))-2*m(2,0)*k(5,0))-2*k(2,0)*m(5,0))+2*m(5,0)*k(5,0))+2*m(0,0)*k(0,0))-2*m(0,0)*k(3,0))-2*k(0,0)*m(3,0))+2*m(3,0)*k(3,0)); groebnerMatrix(0,68) = ((((((((-2*m(0,0)*m(3,0)+pow(m(1,0),2))+pow(m(4,0),2))+pow(m(2,0),2))+pow(m(5,0),2))+pow(m(0,0),2))+pow(m(3,0),2))-2*m(1,0)*m(4,0))-2*m(2,0)*m(5,0)); groebnerMatrix(0,69) = (((((((((((-2*p(1,0)*n(4,0)+2*n(4,0)*p(4,0))+2*n(2,0)*p(2,0))-2*n(2,0)*p(5,0))-2*p(2,0)*n(5,0))+2*n(5,0)*p(5,0))+2*n(0,0)*p(0,0))-2*n(0,0)*p(3,0))-2*p(0,0)*n(3,0))+2*n(3,0)*p(3,0))+2*n(1,0)*p(1,0))-2*n(1,0)*p(4,0)); groebnerMatrix(0,70) = (((((((((((-2*l(1,0)*n(4,0)+2*n(4,0)*l(4,0))+2*n(2,0)*l(2,0))-2*n(2,0)*l(5,0))-2*l(2,0)*n(5,0))+2*n(5,0)*l(5,0))+2*n(0,0)*l(0,0))-2*n(0,0)*l(3,0))-2*l(0,0)*n(3,0))+2*n(3,0)*l(3,0))+2*n(1,0)*l(1,0))-2*n(1,0)*l(4,0)); groebnerMatrix(0,71) = (((((((((((-2*k(1,0)*n(4,0)+2*n(4,0)*k(4,0))+2*n(2,0)*k(2,0))-2*n(2,0)*k(5,0))-2*k(2,0)*n(5,0))+2*n(5,0)*k(5,0))+2*n(0,0)*k(0,0))-2*n(0,0)*k(3,0))-2*k(0,0)*n(3,0))+2*n(3,0)*k(3,0))+2*n(1,0)*k(1,0))-2*n(1,0)*k(4,0)); groebnerMatrix(0,72) = (((((((((((-2*m(1,0)*n(4,0)+2*n(4,0)*m(4,0))+2*n(2,0)*m(2,0))-2*n(2,0)*m(5,0))-2*m(2,0)*n(5,0))+2*n(5,0)*m(5,0))+2*n(0,0)*m(0,0))-2*n(0,0)*m(3,0))-2*m(0,0)*n(3,0))+2*n(3,0)*m(3,0))+2*n(1,0)*m(1,0))-2*n(1,0)*m(4,0)); groebnerMatrix(0,73) = ((((((((-2*n(0,0)*n(3,0)+pow(n(1,0),2))+pow(n(4,0),2))+pow(n(2,0),2))+pow(n(5,0),2))+pow(n(0,0),2))+pow(n(3,0),2))-2*n(1,0)*n(4,0))-2*n(2,0)*n(5,0)); groebnerMatrix(0,74) = (((((((((((2*a(0,0)*p(0,0)-2*a(0,0)*p(3,0))-2*p(0,0)*a(3,0))+2*a(3,0)*p(3,0))+2*a(1,0)*p(1,0))-2*a(1,0)*p(4,0))-2*p(1,0)*a(4,0))+2*a(4,0)*p(4,0))+2*a(2,0)*p(2,0))-2*a(2,0)*p(5,0))-2*p(2,0)*a(5,0))+2*a(5,0)*p(5,0)); groebnerMatrix(0,75) = (((((((((((2*a(0,0)*l(0,0)-2*a(0,0)*l(3,0))-2*l(0,0)*a(3,0))+2*a(3,0)*l(3,0))+2*a(1,0)*l(1,0))-2*a(1,0)*l(4,0))-2*l(1,0)*a(4,0))+2*a(4,0)*l(4,0))+2*a(2,0)*l(2,0))-2*a(2,0)*l(5,0))-2*l(2,0)*a(5,0))+2*a(5,0)*l(5,0)); groebnerMatrix(0,76) = (((((((((((2*a(0,0)*k(0,0)-2*a(0,0)*k(3,0))-2*k(0,0)*a(3,0))+2*a(3,0)*k(3,0))+2*a(1,0)*k(1,0))-2*a(1,0)*k(4,0))-2*k(1,0)*a(4,0))+2*a(4,0)*k(4,0))+2*a(2,0)*k(2,0))-2*a(2,0)*k(5,0))-2*k(2,0)*a(5,0))+2*a(5,0)*k(5,0)); groebnerMatrix(0,77) = (((((((((((2*a(0,0)*m(0,0)-2*a(0,0)*m(3,0))-2*m(0,0)*a(3,0))+2*a(3,0)*m(3,0))+2*a(1,0)*m(1,0))-2*a(1,0)*m(4,0))-2*m(1,0)*a(4,0))+2*a(4,0)*m(4,0))+2*a(2,0)*m(2,0))-2*a(2,0)*m(5,0))-2*m(2,0)*a(5,0))+2*a(5,0)*m(5,0)); groebnerMatrix(0,78) = (((((((((((2*a(0,0)*n(0,0)-2*a(0,0)*n(3,0))-2*n(0,0)*a(3,0))+2*a(3,0)*n(3,0))+2*a(1,0)*n(1,0))-2*a(1,0)*n(4,0))-2*n(1,0)*a(4,0))+2*a(4,0)*n(4,0))+2*a(2,0)*n(2,0))-2*a(2,0)*n(5,0))-2*n(2,0)*a(5,0))+2*a(5,0)*n(5,0)); groebnerMatrix(0,79) = (((((((((-c01w+pow(a(4,0),2))+pow(a(2,0),2))-2*a(2,0)*a(5,0))+pow(a(5,0),2))+pow(a(0,0),2))-2*a(0,0)*a(3,0))+pow(a(3,0),2))+pow(a(1,0),2))-2*a(1,0)*a(4,0)); groebnerMatrix(1,59) = ((((((((pow(p(1,0),2)+pow(p(2,0),2))+pow(p(6,0),2))+pow(p(7,0),2))+pow(p(8,0),2))+pow(p(0,0),2))-2*p(0,0)*p(6,0))-2*p(1,0)*p(7,0))-2*p(2,0)*p(8,0)); groebnerMatrix(1,60) = (((((((((((2*l(1,0)*p(1,0)+2*l(2,0)*p(2,0))-2*l(0,0)*p(6,0))-2*p(0,0)*l(6,0))+2*l(6,0)*p(6,0))-2*l(1,0)*p(7,0))-2*p(1,0)*l(7,0))+2*l(7,0)*p(7,0))-2*l(2,0)*p(8,0))-2*p(2,0)*l(8,0))+2*l(8,0)*p(8,0))+2*l(0,0)*p(0,0)); groebnerMatrix(1,61) = ((((((((pow(l(1,0),2)+pow(l(2,0),2))+pow(l(6,0),2))+pow(l(7,0),2))+pow(l(8,0),2))+pow(l(0,0),2))-2*l(0,0)*l(6,0))-2*l(1,0)*l(7,0))-2*l(2,0)*l(8,0)); groebnerMatrix(1,62) = (((((((((((2*k(1,0)*p(1,0)+2*k(2,0)*p(2,0))-2*k(0,0)*p(6,0))-2*p(0,0)*k(6,0))+2*k(6,0)*p(6,0))-2*k(1,0)*p(7,0))-2*p(1,0)*k(7,0))+2*k(7,0)*p(7,0))-2*k(2,0)*p(8,0))-2*p(2,0)*k(8,0))+2*k(8,0)*p(8,0))+2*k(0,0)*p(0,0)); groebnerMatrix(1,63) = (((((((((((2*k(1,0)*l(1,0)+2*k(2,0)*l(2,0))-2*k(0,0)*l(6,0))-2*l(0,0)*k(6,0))+2*k(6,0)*l(6,0))-2*k(1,0)*l(7,0))-2*l(1,0)*k(7,0))+2*k(7,0)*l(7,0))-2*k(2,0)*l(8,0))-2*l(2,0)*k(8,0))+2*k(8,0)*l(8,0))+2*k(0,0)*l(0,0)); groebnerMatrix(1,64) = ((((((((pow(k(1,0),2)+pow(k(2,0),2))+pow(k(6,0),2))+pow(k(7,0),2))+pow(k(8,0),2))+pow(k(0,0),2))-2*k(0,0)*k(6,0))-2*k(1,0)*k(7,0))-2*k(2,0)*k(8,0)); groebnerMatrix(1,65) = (((((((((((2*m(1,0)*p(1,0)+2*m(2,0)*p(2,0))-2*m(0,0)*p(6,0))-2*p(0,0)*m(6,0))+2*m(6,0)*p(6,0))-2*m(1,0)*p(7,0))-2*p(1,0)*m(7,0))+2*m(7,0)*p(7,0))-2*m(2,0)*p(8,0))-2*p(2,0)*m(8,0))+2*m(8,0)*p(8,0))+2*m(0,0)*p(0,0)); groebnerMatrix(1,66) = (((((((((((2*m(1,0)*l(1,0)+2*m(2,0)*l(2,0))-2*m(0,0)*l(6,0))-2*l(0,0)*m(6,0))+2*m(6,0)*l(6,0))-2*m(1,0)*l(7,0))-2*l(1,0)*m(7,0))+2*m(7,0)*l(7,0))-2*m(2,0)*l(8,0))-2*l(2,0)*m(8,0))+2*m(8,0)*l(8,0))+2*m(0,0)*l(0,0)); groebnerMatrix(1,67) = (((((((((((2*m(1,0)*k(1,0)+2*m(2,0)*k(2,0))-2*m(0,0)*k(6,0))-2*k(0,0)*m(6,0))+2*m(6,0)*k(6,0))-2*m(1,0)*k(7,0))-2*k(1,0)*m(7,0))+2*m(7,0)*k(7,0))-2*m(2,0)*k(8,0))-2*k(2,0)*m(8,0))+2*m(8,0)*k(8,0))+2*m(0,0)*k(0,0)); groebnerMatrix(1,68) = ((((((((pow(m(1,0),2)+pow(m(2,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2))+pow(m(0,0),2))-2*m(0,0)*m(6,0))-2*m(1,0)*m(7,0))-2*m(2,0)*m(8,0)); groebnerMatrix(1,69) = (((((((((((2*n(2,0)*p(2,0)-2*n(0,0)*p(6,0))-2*p(0,0)*n(6,0))+2*n(6,0)*p(6,0))-2*n(1,0)*p(7,0))-2*p(1,0)*n(7,0))+2*n(7,0)*p(7,0))-2*n(2,0)*p(8,0))-2*p(2,0)*n(8,0))+2*n(8,0)*p(8,0))+2*n(0,0)*p(0,0))+2*n(1,0)*p(1,0)); groebnerMatrix(1,70) = (((((((((((2*n(2,0)*l(2,0)-2*n(0,0)*l(6,0))-2*l(0,0)*n(6,0))+2*n(6,0)*l(6,0))-2*n(1,0)*l(7,0))-2*l(1,0)*n(7,0))+2*n(7,0)*l(7,0))-2*n(2,0)*l(8,0))-2*l(2,0)*n(8,0))+2*n(8,0)*l(8,0))+2*n(0,0)*l(0,0))+2*n(1,0)*l(1,0)); groebnerMatrix(1,71) = (((((((((((2*n(2,0)*k(2,0)-2*n(0,0)*k(6,0))-2*k(0,0)*n(6,0))+2*n(6,0)*k(6,0))-2*n(1,0)*k(7,0))-2*k(1,0)*n(7,0))+2*n(7,0)*k(7,0))-2*n(2,0)*k(8,0))-2*k(2,0)*n(8,0))+2*n(8,0)*k(8,0))+2*n(0,0)*k(0,0))+2*n(1,0)*k(1,0)); groebnerMatrix(1,72) = (((((((((((2*n(2,0)*m(2,0)-2*n(0,0)*m(6,0))-2*m(0,0)*n(6,0))+2*n(6,0)*m(6,0))-2*n(1,0)*m(7,0))-2*m(1,0)*n(7,0))+2*n(7,0)*m(7,0))-2*n(2,0)*m(8,0))-2*m(2,0)*n(8,0))+2*n(8,0)*m(8,0))+2*n(0,0)*m(0,0))+2*n(1,0)*m(1,0)); groebnerMatrix(1,73) = ((((((((pow(n(1,0),2)+pow(n(2,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2))+pow(n(0,0),2))-2*n(0,0)*n(6,0))-2*n(1,0)*n(7,0))-2*n(2,0)*n(8,0)); groebnerMatrix(1,74) = (((((((((((-2*a(0,0)*p(6,0)+2*a(0,0)*p(0,0))+2*a(1,0)*p(1,0))+2*a(2,0)*p(2,0))-2*p(0,0)*a(6,0))+2*a(6,0)*p(6,0))-2*a(1,0)*p(7,0))-2*p(1,0)*a(7,0))+2*a(7,0)*p(7,0))-2*a(2,0)*p(8,0))-2*p(2,0)*a(8,0))+2*a(8,0)*p(8,0)); groebnerMatrix(1,75) = (((((((((((2*a(0,0)*l(0,0)+2*a(1,0)*l(1,0))+2*a(2,0)*l(2,0))-2*l(0,0)*a(6,0))+2*a(6,0)*l(6,0))-2*a(1,0)*l(7,0))-2*l(1,0)*a(7,0))+2*a(7,0)*l(7,0))-2*a(2,0)*l(8,0))-2*l(2,0)*a(8,0))+2*a(8,0)*l(8,0))-2*a(0,0)*l(6,0)); groebnerMatrix(1,76) = (((((((((((-2*a(0,0)*k(6,0)+2*a(0,0)*k(0,0))+2*a(1,0)*k(1,0))+2*a(2,0)*k(2,0))-2*k(0,0)*a(6,0))+2*a(6,0)*k(6,0))-2*a(1,0)*k(7,0))-2*k(1,0)*a(7,0))+2*a(7,0)*k(7,0))-2*a(2,0)*k(8,0))-2*k(2,0)*a(8,0))+2*a(8,0)*k(8,0)); groebnerMatrix(1,77) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))-2*m(0,0)*a(6,0))+2*a(6,0)*m(6,0))-2*a(1,0)*m(7,0))-2*m(1,0)*a(7,0))+2*a(7,0)*m(7,0))-2*a(2,0)*m(8,0))-2*m(2,0)*a(8,0))+2*a(8,0)*m(8,0))-2*a(0,0)*m(6,0)); groebnerMatrix(1,78) = (((((((((((2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))-2*n(0,0)*a(6,0))+2*a(6,0)*n(6,0))-2*a(1,0)*n(7,0))-2*n(1,0)*a(7,0))+2*a(7,0)*n(7,0))-2*a(2,0)*n(8,0))-2*n(2,0)*a(8,0))+2*a(8,0)*n(8,0))-2*a(0,0)*n(6,0)); groebnerMatrix(1,79) = (((((((((-c02w+pow(a(2,0),2))-2*a(0,0)*a(6,0))+pow(a(6,0),2))-2*a(1,0)*a(7,0))+pow(a(7,0),2))-2*a(2,0)*a(8,0))+pow(a(8,0),2))+pow(a(0,0),2))+pow(a(1,0),2)); groebnerMatrix(2,59) = ((((((((pow(p(1,0),2)+pow(p(2,0),2))+pow(p(9,0),2))+pow(p(10,0),2))+pow(p(11,0),2))+pow(p(0,0),2))-2*p(0,0)*p(9,0))-2*p(1,0)*p(10,0))-2*p(2,0)*p(11,0)); groebnerMatrix(2,60) = (((((((((((2*l(1,0)*p(1,0)+2*l(2,0)*p(2,0))-2*l(0,0)*p(9,0))-2*p(0,0)*l(9,0))+2*l(9,0)*p(9,0))-2*l(1,0)*p(10,0))-2*p(1,0)*l(10,0))+2*l(10,0)*p(10,0))-2*l(2,0)*p(11,0))-2*p(2,0)*l(11,0))+2*l(11,0)*p(11,0))+2*l(0,0)*p(0,0)); groebnerMatrix(2,61) = ((((((((pow(l(1,0),2)+pow(l(2,0),2))+pow(l(9,0),2))+pow(l(10,0),2))+pow(l(11,0),2))+pow(l(0,0),2))-2*l(0,0)*l(9,0))-2*l(1,0)*l(10,0))-2*l(2,0)*l(11,0)); groebnerMatrix(2,62) = (((((((((((2*k(1,0)*p(1,0)+2*k(2,0)*p(2,0))-2*k(0,0)*p(9,0))-2*p(0,0)*k(9,0))+2*k(9,0)*p(9,0))-2*k(1,0)*p(10,0))-2*p(1,0)*k(10,0))+2*k(10,0)*p(10,0))-2*k(2,0)*p(11,0))-2*p(2,0)*k(11,0))+2*k(11,0)*p(11,0))+2*k(0,0)*p(0,0)); groebnerMatrix(2,63) = (((((((((((2*k(1,0)*l(1,0)+2*k(2,0)*l(2,0))-2*k(0,0)*l(9,0))-2*l(0,0)*k(9,0))+2*k(9,0)*l(9,0))-2*k(1,0)*l(10,0))-2*l(1,0)*k(10,0))+2*k(10,0)*l(10,0))-2*k(2,0)*l(11,0))-2*l(2,0)*k(11,0))+2*k(11,0)*l(11,0))+2*k(0,0)*l(0,0)); groebnerMatrix(2,64) = ((((((((-2*k(0,0)*k(9,0)+pow(k(1,0),2))+pow(k(2,0),2))+pow(k(9,0),2))+pow(k(10,0),2))+pow(k(11,0),2))+pow(k(0,0),2))-2*k(1,0)*k(10,0))-2*k(2,0)*k(11,0)); groebnerMatrix(2,65) = (((((((((((-2*m(0,0)*p(9,0)+2*m(1,0)*p(1,0))+2*m(2,0)*p(2,0))-2*p(0,0)*m(9,0))+2*m(9,0)*p(9,0))-2*m(1,0)*p(10,0))-2*p(1,0)*m(10,0))+2*m(10,0)*p(10,0))-2*m(2,0)*p(11,0))-2*p(2,0)*m(11,0))+2*m(11,0)*p(11,0))+2*m(0,0)*p(0,0)); groebnerMatrix(2,66) = (((((((((((-2*m(0,0)*l(9,0)+2*m(1,0)*l(1,0))+2*m(2,0)*l(2,0))-2*l(0,0)*m(9,0))+2*m(9,0)*l(9,0))-2*m(1,0)*l(10,0))-2*l(1,0)*m(10,0))+2*m(10,0)*l(10,0))-2*m(2,0)*l(11,0))-2*l(2,0)*m(11,0))+2*m(11,0)*l(11,0))+2*m(0,0)*l(0,0)); groebnerMatrix(2,67) = (((((((((((-2*m(0,0)*k(9,0)+2*m(1,0)*k(1,0))+2*m(2,0)*k(2,0))-2*k(0,0)*m(9,0))+2*m(9,0)*k(9,0))-2*m(1,0)*k(10,0))-2*k(1,0)*m(10,0))+2*m(10,0)*k(10,0))-2*m(2,0)*k(11,0))-2*k(2,0)*m(11,0))+2*m(11,0)*k(11,0))+2*m(0,0)*k(0,0)); groebnerMatrix(2,68) = ((((((((pow(m(1,0),2)+pow(m(2,0),2))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2))+pow(m(0,0),2))-2*m(1,0)*m(10,0))-2*m(2,0)*m(11,0))-2*m(0,0)*m(9,0)); groebnerMatrix(2,69) = (((((((((((-2*n(0,0)*p(9,0)+2*n(2,0)*p(2,0))-2*p(0,0)*n(9,0))+2*n(9,0)*p(9,0))-2*n(1,0)*p(10,0))-2*p(1,0)*n(10,0))+2*n(10,0)*p(10,0))-2*n(2,0)*p(11,0))-2*p(2,0)*n(11,0))+2*n(11,0)*p(11,0))+2*n(0,0)*p(0,0))+2*n(1,0)*p(1,0)); groebnerMatrix(2,70) = (((((((((((-2*n(0,0)*l(9,0)+2*n(2,0)*l(2,0))-2*l(0,0)*n(9,0))+2*n(9,0)*l(9,0))-2*n(1,0)*l(10,0))-2*l(1,0)*n(10,0))+2*n(10,0)*l(10,0))-2*n(2,0)*l(11,0))-2*l(2,0)*n(11,0))+2*n(11,0)*l(11,0))+2*n(0,0)*l(0,0))+2*n(1,0)*l(1,0)); groebnerMatrix(2,71) = (((((((((((-2*n(0,0)*k(9,0)+2*n(2,0)*k(2,0))-2*k(0,0)*n(9,0))+2*n(9,0)*k(9,0))-2*n(1,0)*k(10,0))-2*k(1,0)*n(10,0))+2*n(10,0)*k(10,0))-2*n(2,0)*k(11,0))-2*k(2,0)*n(11,0))+2*n(11,0)*k(11,0))+2*n(0,0)*k(0,0))+2*n(1,0)*k(1,0)); groebnerMatrix(2,72) = (((((((((((-2*n(0,0)*m(9,0)-2*m(0,0)*n(9,0))+2*n(2,0)*m(2,0))+2*n(9,0)*m(9,0))-2*n(1,0)*m(10,0))-2*m(1,0)*n(10,0))+2*n(10,0)*m(10,0))-2*n(2,0)*m(11,0))-2*m(2,0)*n(11,0))+2*n(11,0)*m(11,0))+2*n(0,0)*m(0,0))+2*n(1,0)*m(1,0)); groebnerMatrix(2,73) = ((((((((pow(n(1,0),2)+pow(n(2,0),2))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2))+pow(n(0,0),2))-2*n(1,0)*n(10,0))-2*n(2,0)*n(11,0))-2*n(0,0)*n(9,0)); groebnerMatrix(2,74) = (((((((((((-2*a(0,0)*p(9,0)+2*a(0,0)*p(0,0))+2*a(1,0)*p(1,0))+2*a(2,0)*p(2,0))-2*p(0,0)*a(9,0))+2*a(9,0)*p(9,0))-2*a(1,0)*p(10,0))-2*p(1,0)*a(10,0))+2*a(10,0)*p(10,0))-2*a(2,0)*p(11,0))-2*p(2,0)*a(11,0))+2*a(11,0)*p(11,0)); groebnerMatrix(2,75) = (((((((((((-2*a(0,0)*l(9,0)+2*a(0,0)*l(0,0))+2*a(1,0)*l(1,0))+2*a(2,0)*l(2,0))-2*l(0,0)*a(9,0))+2*a(9,0)*l(9,0))-2*a(1,0)*l(10,0))-2*l(1,0)*a(10,0))+2*a(10,0)*l(10,0))-2*a(2,0)*l(11,0))-2*l(2,0)*a(11,0))+2*a(11,0)*l(11,0)); groebnerMatrix(2,76) = (((((((((((2*a(0,0)*k(0,0)+2*a(1,0)*k(1,0))+2*a(2,0)*k(2,0))+2*a(9,0)*k(9,0))-2*a(1,0)*k(10,0))-2*k(1,0)*a(10,0))+2*a(10,0)*k(10,0))-2*a(2,0)*k(11,0))-2*k(2,0)*a(11,0))+2*a(11,0)*k(11,0))-2*k(0,0)*a(9,0))-2*a(0,0)*k(9,0)); groebnerMatrix(2,77) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))+2*a(9,0)*m(9,0))-2*a(1,0)*m(10,0))-2*m(1,0)*a(10,0))+2*a(10,0)*m(10,0))-2*a(2,0)*m(11,0))-2*m(2,0)*a(11,0))+2*a(11,0)*m(11,0))-2*m(0,0)*a(9,0))-2*a(0,0)*m(9,0)); groebnerMatrix(2,78) = (((((((((((-2*a(0,0)*n(9,0)+2*a(0,0)*n(0,0))+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))+2*a(9,0)*n(9,0))-2*a(1,0)*n(10,0))-2*n(1,0)*a(10,0))+2*a(10,0)*n(10,0))-2*a(2,0)*n(11,0))-2*n(2,0)*a(11,0))+2*a(11,0)*n(11,0))-2*n(0,0)*a(9,0)); groebnerMatrix(2,79) = (((((((((-c03w+pow(a(2,0),2))-2*a(0,0)*a(9,0))+pow(a(9,0),2))-2*a(1,0)*a(10,0))+pow(a(10,0),2))-2*a(2,0)*a(11,0))+pow(a(11,0),2))+pow(a(0,0),2))+pow(a(1,0),2)); groebnerMatrix(3,59) = ((((((((pow(p(4,0),2)+pow(p(5,0),2))+pow(p(6,0),2))+pow(p(7,0),2))+pow(p(8,0),2))+pow(p(3,0),2))-2*p(3,0)*p(6,0))-2*p(4,0)*p(7,0))-2*p(5,0)*p(8,0)); groebnerMatrix(3,60) = (((((((((((2*l(4,0)*p(4,0)+2*l(5,0)*p(5,0))+2*l(6,0)*p(6,0))+2*l(7,0)*p(7,0))+2*l(8,0)*p(8,0))-2*l(4,0)*p(7,0))-2*p(4,0)*l(7,0))-2*l(3,0)*p(6,0))-2*p(3,0)*l(6,0))-2*l(5,0)*p(8,0))-2*p(5,0)*l(8,0))+2*l(3,0)*p(3,0)); groebnerMatrix(3,61) = ((((((((pow(l(4,0),2)+pow(l(5,0),2))+pow(l(6,0),2))+pow(l(7,0),2))+pow(l(8,0),2))+pow(l(3,0),2))-2*l(3,0)*l(6,0))-2*l(4,0)*l(7,0))-2*l(5,0)*l(8,0)); groebnerMatrix(3,62) = (((((((((((2*k(4,0)*p(4,0)+2*k(5,0)*p(5,0))+2*k(6,0)*p(6,0))+2*k(7,0)*p(7,0))+2*k(8,0)*p(8,0))-2*k(5,0)*p(8,0))-2*k(4,0)*p(7,0))-2*p(4,0)*k(7,0))-2*k(3,0)*p(6,0))-2*p(3,0)*k(6,0))-2*p(5,0)*k(8,0))+2*k(3,0)*p(3,0)); groebnerMatrix(3,63) = (((((((((((2*k(4,0)*l(4,0)+2*k(5,0)*l(5,0))+2*k(6,0)*l(6,0))+2*k(7,0)*l(7,0))+2*k(8,0)*l(8,0))-2*k(5,0)*l(8,0))-2*k(4,0)*l(7,0))-2*l(4,0)*k(7,0))-2*k(3,0)*l(6,0))-2*l(3,0)*k(6,0))-2*l(5,0)*k(8,0))+2*k(3,0)*l(3,0)); groebnerMatrix(3,64) = ((((((((pow(k(4,0),2)+pow(k(5,0),2))+pow(k(6,0),2))+pow(k(7,0),2))+pow(k(8,0),2))+pow(k(3,0),2))-2*k(5,0)*k(8,0))-2*k(3,0)*k(6,0))-2*k(4,0)*k(7,0)); groebnerMatrix(3,65) = (((((((((((2*m(4,0)*p(4,0)+2*m(5,0)*p(5,0))+2*m(6,0)*p(6,0))+2*m(7,0)*p(7,0))+2*m(8,0)*p(8,0))-2*m(4,0)*p(7,0))-2*p(4,0)*m(7,0))-2*m(5,0)*p(8,0))-2*m(3,0)*p(6,0))-2*p(3,0)*m(6,0))-2*p(5,0)*m(8,0))+2*m(3,0)*p(3,0)); groebnerMatrix(3,66) = (((((((((((2*m(4,0)*l(4,0)+2*m(5,0)*l(5,0))+2*m(6,0)*l(6,0))+2*m(7,0)*l(7,0))+2*m(8,0)*l(8,0))-2*m(4,0)*l(7,0))-2*l(4,0)*m(7,0))-2*m(5,0)*l(8,0))-2*m(3,0)*l(6,0))-2*l(3,0)*m(6,0))-2*l(5,0)*m(8,0))+2*m(3,0)*l(3,0)); groebnerMatrix(3,67) = (((((((((((2*m(4,0)*k(4,0)+2*m(5,0)*k(5,0))+2*m(6,0)*k(6,0))+2*m(7,0)*k(7,0))+2*m(8,0)*k(8,0))-2*k(5,0)*m(8,0))-2*m(4,0)*k(7,0))-2*k(4,0)*m(7,0))-2*m(5,0)*k(8,0))-2*m(3,0)*k(6,0))-2*k(3,0)*m(6,0))+2*m(3,0)*k(3,0)); groebnerMatrix(3,68) = ((((((((pow(m(4,0),2)+pow(m(5,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2))+pow(m(3,0),2))-2*m(3,0)*m(6,0))-2*m(4,0)*m(7,0))-2*m(5,0)*m(8,0)); groebnerMatrix(3,69) = (((((((((((2*n(4,0)*p(4,0)+2*n(5,0)*p(5,0))+2*n(6,0)*p(6,0))+2*n(7,0)*p(7,0))+2*n(8,0)*p(8,0))-2*p(4,0)*n(7,0))-2*n(5,0)*p(8,0))-2*n(3,0)*p(6,0))-2*p(3,0)*n(6,0))-2*n(4,0)*p(7,0))-2*p(5,0)*n(8,0))+2*n(3,0)*p(3,0)); groebnerMatrix(3,70) = (((((((((((2*n(4,0)*l(4,0)+2*n(5,0)*l(5,0))+2*n(6,0)*l(6,0))+2*n(7,0)*l(7,0))+2*n(8,0)*l(8,0))-2*l(4,0)*n(7,0))-2*n(5,0)*l(8,0))-2*n(3,0)*l(6,0))-2*l(3,0)*n(6,0))-2*n(4,0)*l(7,0))-2*l(5,0)*n(8,0))+2*n(3,0)*l(3,0)); groebnerMatrix(3,71) = (((((((((((2*n(4,0)*k(4,0)+2*n(5,0)*k(5,0))+2*n(6,0)*k(6,0))+2*n(7,0)*k(7,0))+2*n(8,0)*k(8,0))-2*k(5,0)*n(8,0))-2*k(4,0)*n(7,0))-2*n(5,0)*k(8,0))-2*n(3,0)*k(6,0))-2*k(3,0)*n(6,0))-2*n(4,0)*k(7,0))+2*n(3,0)*k(3,0)); groebnerMatrix(3,72) = (((((((((((2*n(4,0)*m(4,0)+2*n(5,0)*m(5,0))+2*n(6,0)*m(6,0))+2*n(7,0)*m(7,0))+2*n(8,0)*m(8,0))-2*m(4,0)*n(7,0))-2*n(5,0)*m(8,0))-2*m(5,0)*n(8,0))-2*n(3,0)*m(6,0))-2*m(3,0)*n(6,0))-2*n(4,0)*m(7,0))+2*n(3,0)*m(3,0)); groebnerMatrix(3,73) = ((((((((pow(n(4,0),2)+pow(n(5,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2))+pow(n(3,0),2))-2*n(3,0)*n(6,0))-2*n(4,0)*n(7,0))-2*n(5,0)*n(8,0)); groebnerMatrix(3,74) = (((((((((((-2*a(3,0)*p(6,0)+2*a(3,0)*p(3,0))+2*a(4,0)*p(4,0))+2*a(5,0)*p(5,0))+2*a(6,0)*p(6,0))+2*a(7,0)*p(7,0))+2*a(8,0)*p(8,0))-2*p(3,0)*a(6,0))-2*a(4,0)*p(7,0))-2*p(4,0)*a(7,0))-2*a(5,0)*p(8,0))-2*p(5,0)*a(8,0)); groebnerMatrix(3,75) = (((((((((((2*a(3,0)*l(3,0)+2*a(4,0)*l(4,0))+2*a(5,0)*l(5,0))+2*a(6,0)*l(6,0))+2*a(7,0)*l(7,0))+2*a(8,0)*l(8,0))-2*l(3,0)*a(6,0))-2*a(4,0)*l(7,0))-2*l(4,0)*a(7,0))-2*a(5,0)*l(8,0))-2*l(5,0)*a(8,0))-2*a(3,0)*l(6,0)); groebnerMatrix(3,76) = (((((((((((2*a(3,0)*k(3,0)-2*k(5,0)*a(8,0))+2*a(4,0)*k(4,0))+2*a(5,0)*k(5,0))+2*a(6,0)*k(6,0))+2*a(7,0)*k(7,0))+2*a(8,0)*k(8,0))-2*k(3,0)*a(6,0))-2*a(4,0)*k(7,0))-2*k(4,0)*a(7,0))-2*a(5,0)*k(8,0))-2*a(3,0)*k(6,0)); groebnerMatrix(3,77) = (((((((((((2*a(3,0)*m(3,0)+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(6,0)*m(6,0))+2*a(7,0)*m(7,0))+2*a(8,0)*m(8,0))-2*m(3,0)*a(6,0))-2*a(4,0)*m(7,0))-2*m(4,0)*a(7,0))-2*a(5,0)*m(8,0))-2*m(5,0)*a(8,0))-2*a(3,0)*m(6,0)); groebnerMatrix(3,78) = (((((((((((2*a(3,0)*n(3,0)+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(6,0)*n(6,0))+2*a(7,0)*n(7,0))+2*a(8,0)*n(8,0))-2*n(3,0)*a(6,0))-2*a(4,0)*n(7,0))-2*n(4,0)*a(7,0))-2*a(5,0)*n(8,0))-2*n(5,0)*a(8,0))-2*a(3,0)*n(6,0)); groebnerMatrix(3,79) = (((((((((-c12w+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(6,0),2))+pow(a(7,0),2))+pow(a(8,0),2))-2*a(3,0)*a(6,0))-2*a(4,0)*a(7,0))+pow(a(3,0),2))-2*a(5,0)*a(8,0)); groebnerMatrix(4,59) = ((((((((pow(p(4,0),2)+pow(p(5,0),2))+pow(p(9,0),2))+pow(p(10,0),2))+pow(p(11,0),2))+pow(p(3,0),2))-2*p(3,0)*p(9,0))-2*p(4,0)*p(10,0))-2*p(5,0)*p(11,0)); groebnerMatrix(4,60) = (((((((((((2*l(4,0)*p(4,0)+2*l(5,0)*p(5,0))+2*l(9,0)*p(9,0))+2*l(10,0)*p(10,0))+2*l(11,0)*p(11,0))-2*l(3,0)*p(9,0))-2*p(3,0)*l(9,0))-2*l(4,0)*p(10,0))-2*p(4,0)*l(10,0))-2*l(5,0)*p(11,0))-2*p(5,0)*l(11,0))+2*l(3,0)*p(3,0)); groebnerMatrix(4,61) = ((((((((pow(l(4,0),2)+pow(l(5,0),2))+pow(l(9,0),2))+pow(l(10,0),2))+pow(l(11,0),2))+pow(l(3,0),2))-2*l(3,0)*l(9,0))-2*l(4,0)*l(10,0))-2*l(5,0)*l(11,0)); groebnerMatrix(4,62) = (((((((((((2*k(4,0)*p(4,0)+2*k(5,0)*p(5,0))+2*k(9,0)*p(9,0))+2*k(10,0)*p(10,0))+2*k(11,0)*p(11,0))-2*k(3,0)*p(9,0))-2*p(3,0)*k(9,0))-2*k(4,0)*p(10,0))-2*p(4,0)*k(10,0))-2*k(5,0)*p(11,0))-2*p(5,0)*k(11,0))+2*k(3,0)*p(3,0)); groebnerMatrix(4,63) = (((((((((((2*k(4,0)*l(4,0)+2*k(5,0)*l(5,0))+2*k(9,0)*l(9,0))+2*k(10,0)*l(10,0))+2*k(11,0)*l(11,0))-2*k(3,0)*l(9,0))-2*l(3,0)*k(9,0))-2*k(4,0)*l(10,0))-2*l(4,0)*k(10,0))-2*k(5,0)*l(11,0))-2*l(5,0)*k(11,0))+2*k(3,0)*l(3,0)); groebnerMatrix(4,64) = ((((((((pow(k(4,0),2)+pow(k(5,0),2))+pow(k(9,0),2))+pow(k(10,0),2))+pow(k(11,0),2))+pow(k(3,0),2))-2*k(3,0)*k(9,0))-2*k(4,0)*k(10,0))-2*k(5,0)*k(11,0)); groebnerMatrix(4,65) = (((((((((((2*m(4,0)*p(4,0)+2*m(5,0)*p(5,0))+2*m(9,0)*p(9,0))+2*m(10,0)*p(10,0))+2*m(11,0)*p(11,0))-2*m(3,0)*p(9,0))-2*p(3,0)*m(9,0))-2*m(4,0)*p(10,0))-2*p(4,0)*m(10,0))-2*m(5,0)*p(11,0))-2*p(5,0)*m(11,0))+2*m(3,0)*p(3,0)); groebnerMatrix(4,66) = (((((((((((2*m(4,0)*l(4,0)+2*m(5,0)*l(5,0))+2*m(9,0)*l(9,0))+2*m(10,0)*l(10,0))+2*m(11,0)*l(11,0))-2*m(3,0)*l(9,0))-2*l(3,0)*m(9,0))-2*m(4,0)*l(10,0))-2*l(4,0)*m(10,0))-2*m(5,0)*l(11,0))-2*l(5,0)*m(11,0))+2*m(3,0)*l(3,0)); groebnerMatrix(4,67) = (((((((((((2*m(4,0)*k(4,0)+2*m(5,0)*k(5,0))+2*m(9,0)*k(9,0))+2*m(10,0)*k(10,0))+2*m(11,0)*k(11,0))-2*m(3,0)*k(9,0))-2*k(3,0)*m(9,0))-2*m(4,0)*k(10,0))-2*k(4,0)*m(10,0))-2*m(5,0)*k(11,0))-2*k(5,0)*m(11,0))+2*m(3,0)*k(3,0)); groebnerMatrix(4,68) = ((((((((pow(m(4,0),2)+pow(m(5,0),2))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2))+pow(m(3,0),2))-2*m(3,0)*m(9,0))-2*m(4,0)*m(10,0))-2*m(5,0)*m(11,0)); groebnerMatrix(4,69) = (((((((((((2*n(4,0)*p(4,0)+2*n(5,0)*p(5,0))+2*n(9,0)*p(9,0))+2*n(10,0)*p(10,0))+2*n(11,0)*p(11,0))-2*n(3,0)*p(9,0))-2*p(3,0)*n(9,0))-2*n(4,0)*p(10,0))-2*p(4,0)*n(10,0))-2*n(5,0)*p(11,0))-2*p(5,0)*n(11,0))+2*n(3,0)*p(3,0)); groebnerMatrix(4,70) = (((((((((((2*n(4,0)*l(4,0)+2*n(5,0)*l(5,0))+2*n(9,0)*l(9,0))+2*n(10,0)*l(10,0))+2*n(11,0)*l(11,0))-2*n(3,0)*l(9,0))-2*l(3,0)*n(9,0))-2*n(4,0)*l(10,0))-2*l(4,0)*n(10,0))-2*n(5,0)*l(11,0))-2*l(5,0)*n(11,0))+2*n(3,0)*l(3,0)); groebnerMatrix(4,71) = (((((((((((2*n(4,0)*k(4,0)+2*n(5,0)*k(5,0))+2*n(9,0)*k(9,0))+2*n(10,0)*k(10,0))+2*n(11,0)*k(11,0))-2*n(3,0)*k(9,0))-2*k(3,0)*n(9,0))-2*n(4,0)*k(10,0))-2*k(4,0)*n(10,0))-2*n(5,0)*k(11,0))-2*k(5,0)*n(11,0))+2*n(3,0)*k(3,0)); groebnerMatrix(4,72) = (((((((((((2*n(4,0)*m(4,0)+2*n(5,0)*m(5,0))+2*n(9,0)*m(9,0))+2*n(10,0)*m(10,0))+2*n(11,0)*m(11,0))-2*n(3,0)*m(9,0))-2*m(3,0)*n(9,0))-2*n(4,0)*m(10,0))-2*m(4,0)*n(10,0))-2*n(5,0)*m(11,0))-2*m(5,0)*n(11,0))+2*n(3,0)*m(3,0)); groebnerMatrix(4,73) = ((((((((pow(n(4,0),2)+pow(n(5,0),2))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2))+pow(n(3,0),2))-2*n(3,0)*n(9,0))-2*n(4,0)*n(10,0))-2*n(5,0)*n(11,0)); groebnerMatrix(4,74) = (((((((((((2*a(3,0)*p(3,0)+2*a(4,0)*p(4,0))+2*a(5,0)*p(5,0))+2*a(9,0)*p(9,0))+2*a(10,0)*p(10,0))+2*a(11,0)*p(11,0))-2*a(3,0)*p(9,0))-2*p(3,0)*a(9,0))-2*a(4,0)*p(10,0))-2*p(4,0)*a(10,0))-2*a(5,0)*p(11,0))-2*p(5,0)*a(11,0)); groebnerMatrix(4,75) = (((((((((((2*a(3,0)*l(3,0)+2*a(4,0)*l(4,0))+2*a(5,0)*l(5,0))+2*a(9,0)*l(9,0))+2*a(10,0)*l(10,0))+2*a(11,0)*l(11,0))-2*a(3,0)*l(9,0))-2*l(3,0)*a(9,0))-2*a(4,0)*l(10,0))-2*l(4,0)*a(10,0))-2*a(5,0)*l(11,0))-2*l(5,0)*a(11,0)); groebnerMatrix(4,76) = (((((((((((2*a(3,0)*k(3,0)+2*a(4,0)*k(4,0))+2*a(5,0)*k(5,0))+2*a(9,0)*k(9,0))+2*a(10,0)*k(10,0))+2*a(11,0)*k(11,0))-2*a(3,0)*k(9,0))-2*k(3,0)*a(9,0))-2*a(4,0)*k(10,0))-2*k(4,0)*a(10,0))-2*a(5,0)*k(11,0))-2*k(5,0)*a(11,0)); groebnerMatrix(4,77) = (((((((((((2*a(3,0)*m(3,0)+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(9,0)*m(9,0))+2*a(10,0)*m(10,0))+2*a(11,0)*m(11,0))-2*a(3,0)*m(9,0))-2*m(3,0)*a(9,0))-2*a(4,0)*m(10,0))-2*m(4,0)*a(10,0))-2*a(5,0)*m(11,0))-2*m(5,0)*a(11,0)); groebnerMatrix(4,78) = (((((((((((2*a(3,0)*n(3,0)+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(9,0)*n(9,0))+2*a(10,0)*n(10,0))+2*a(11,0)*n(11,0))-2*a(3,0)*n(9,0))-2*n(3,0)*a(9,0))-2*a(4,0)*n(10,0))-2*n(4,0)*a(10,0))-2*a(5,0)*n(11,0))-2*n(5,0)*a(11,0)); groebnerMatrix(4,79) = (((((((((-c13w+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(9,0),2))+pow(a(10,0),2))+pow(a(11,0),2))+pow(a(3,0),2))-2*a(3,0)*a(9,0))-2*a(4,0)*a(10,0))-2*a(5,0)*a(11,0)); groebnerMatrix(5,59) = ((((((((pow(p(6,0),2)+pow(p(7,0),2))+pow(p(8,0),2))+pow(p(9,0),2))+pow(p(10,0),2))+pow(p(11,0),2))-2*p(8,0)*p(11,0))-2*p(6,0)*p(9,0))-2*p(7,0)*p(10,0)); groebnerMatrix(5,60) = (((((((((((2*l(6,0)*p(6,0)+2*l(7,0)*p(7,0))+2*l(8,0)*p(8,0))+2*l(9,0)*p(9,0))+2*l(10,0)*p(10,0))+2*l(11,0)*p(11,0))-2*l(6,0)*p(9,0))-2*p(6,0)*l(9,0))-2*l(7,0)*p(10,0))-2*p(7,0)*l(10,0))-2*l(8,0)*p(11,0))-2*p(8,0)*l(11,0)); groebnerMatrix(5,61) = ((((((((pow(l(6,0),2)+pow(l(7,0),2))+pow(l(8,0),2))+pow(l(9,0),2))+pow(l(10,0),2))+pow(l(11,0),2))-2*l(8,0)*l(11,0))-2*l(6,0)*l(9,0))-2*l(7,0)*l(10,0)); groebnerMatrix(5,62) = (((((((((((2*k(6,0)*p(6,0)+2*k(7,0)*p(7,0))+2*k(8,0)*p(8,0))+2*k(9,0)*p(9,0))+2*k(10,0)*p(10,0))+2*k(11,0)*p(11,0))-2*k(7,0)*p(10,0))-2*k(6,0)*p(9,0))-2*p(6,0)*k(9,0))-2*p(7,0)*k(10,0))-2*k(8,0)*p(11,0))-2*p(8,0)*k(11,0)); groebnerMatrix(5,63) = (((((((((((2*k(6,0)*l(6,0)+2*k(7,0)*l(7,0))+2*k(8,0)*l(8,0))+2*k(9,0)*l(9,0))+2*k(10,0)*l(10,0))+2*k(11,0)*l(11,0))-2*k(7,0)*l(10,0))-2*l(7,0)*k(10,0))-2*k(6,0)*l(9,0))-2*l(6,0)*k(9,0))-2*k(8,0)*l(11,0))-2*l(8,0)*k(11,0)); groebnerMatrix(5,64) = ((((((((pow(k(6,0),2)+pow(k(7,0),2))+pow(k(8,0),2))+pow(k(9,0),2))+pow(k(10,0),2))+pow(k(11,0),2))-2*k(8,0)*k(11,0))-2*k(6,0)*k(9,0))-2*k(7,0)*k(10,0)); groebnerMatrix(5,65) = (((((((((((2*m(6,0)*p(6,0)+2*m(7,0)*p(7,0))+2*m(8,0)*p(8,0))+2*m(9,0)*p(9,0))+2*m(10,0)*p(10,0))+2*m(11,0)*p(11,0))-2*m(6,0)*p(9,0))-2*p(6,0)*m(9,0))-2*m(7,0)*p(10,0))-2*p(7,0)*m(10,0))-2*m(8,0)*p(11,0))-2*p(8,0)*m(11,0)); groebnerMatrix(5,66) = (((((((((((2*m(6,0)*l(6,0)+2*m(7,0)*l(7,0))+2*m(8,0)*l(8,0))+2*m(9,0)*l(9,0))+2*m(10,0)*l(10,0))+2*m(11,0)*l(11,0))-2*l(7,0)*m(10,0))-2*m(6,0)*l(9,0))-2*l(6,0)*m(9,0))-2*m(7,0)*l(10,0))-2*m(8,0)*l(11,0))-2*l(8,0)*m(11,0)); groebnerMatrix(5,67) = (((((((((((2*m(6,0)*k(6,0)+2*m(7,0)*k(7,0))+2*m(8,0)*k(8,0))+2*m(9,0)*k(9,0))+2*m(10,0)*k(10,0))+2*m(11,0)*k(11,0))-2*k(7,0)*m(10,0))-2*m(6,0)*k(9,0))-2*k(6,0)*m(9,0))-2*m(7,0)*k(10,0))-2*m(8,0)*k(11,0))-2*k(8,0)*m(11,0)); groebnerMatrix(5,68) = ((((((((pow(m(6,0),2)+pow(m(7,0),2))+pow(m(8,0),2))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2))-2*m(8,0)*m(11,0))-2*m(6,0)*m(9,0))-2*m(7,0)*m(10,0)); groebnerMatrix(5,69) = (((((((((((2*n(6,0)*p(6,0)+2*n(7,0)*p(7,0))+2*n(8,0)*p(8,0))+2*n(9,0)*p(9,0))+2*n(10,0)*p(10,0))+2*n(11,0)*p(11,0))-2*n(6,0)*p(9,0))-2*p(6,0)*n(9,0))-2*n(7,0)*p(10,0))-2*p(7,0)*n(10,0))-2*n(8,0)*p(11,0))-2*p(8,0)*n(11,0)); groebnerMatrix(5,70) = (((((((((((2*n(6,0)*l(6,0)+2*n(7,0)*l(7,0))+2*n(8,0)*l(8,0))+2*n(9,0)*l(9,0))+2*n(10,0)*l(10,0))+2*n(11,0)*l(11,0))-2*l(7,0)*n(10,0))-2*n(6,0)*l(9,0))-2*l(6,0)*n(9,0))-2*n(7,0)*l(10,0))-2*n(8,0)*l(11,0))-2*l(8,0)*n(11,0)); groebnerMatrix(5,71) = (((((((((((2*n(6,0)*k(6,0)+2*n(7,0)*k(7,0))+2*n(8,0)*k(8,0))+2*n(9,0)*k(9,0))+2*n(10,0)*k(10,0))+2*n(11,0)*k(11,0))-2*k(7,0)*n(10,0))-2*n(6,0)*k(9,0))-2*k(6,0)*n(9,0))-2*n(7,0)*k(10,0))-2*n(8,0)*k(11,0))-2*k(8,0)*n(11,0)); groebnerMatrix(5,72) = (((((((((((2*n(6,0)*m(6,0)+2*n(7,0)*m(7,0))+2*n(8,0)*m(8,0))+2*n(9,0)*m(9,0))+2*n(10,0)*m(10,0))+2*n(11,0)*m(11,0))-2*n(6,0)*m(9,0))-2*m(6,0)*n(9,0))-2*n(7,0)*m(10,0))-2*m(7,0)*n(10,0))-2*n(8,0)*m(11,0))-2*m(8,0)*n(11,0)); groebnerMatrix(5,73) = ((((((((pow(n(6,0),2)+pow(n(7,0),2))+pow(n(8,0),2))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2))-2*n(8,0)*n(11,0))-2*n(6,0)*n(9,0))-2*n(7,0)*n(10,0)); groebnerMatrix(5,74) = (((((((((((2*a(6,0)*p(6,0)+2*a(7,0)*p(7,0))+2*a(8,0)*p(8,0))+2*a(9,0)*p(9,0))+2*a(10,0)*p(10,0))+2*a(11,0)*p(11,0))-2*a(8,0)*p(11,0))-2*p(8,0)*a(11,0))-2*a(6,0)*p(9,0))-2*p(6,0)*a(9,0))-2*a(7,0)*p(10,0))-2*p(7,0)*a(10,0)); groebnerMatrix(5,75) = (((((((((((2*a(6,0)*l(6,0)+2*a(7,0)*l(7,0))+2*a(8,0)*l(8,0))+2*a(9,0)*l(9,0))+2*a(10,0)*l(10,0))+2*a(11,0)*l(11,0))-2*a(8,0)*l(11,0))-2*l(8,0)*a(11,0))-2*a(6,0)*l(9,0))-2*l(6,0)*a(9,0))-2*a(7,0)*l(10,0))-2*l(7,0)*a(10,0)); groebnerMatrix(5,76) = (((((((((((2*a(6,0)*k(6,0)+2*a(7,0)*k(7,0))+2*a(8,0)*k(8,0))+2*a(9,0)*k(9,0))+2*a(10,0)*k(10,0))+2*a(11,0)*k(11,0))-2*a(8,0)*k(11,0))-2*k(8,0)*a(11,0))-2*a(6,0)*k(9,0))-2*k(6,0)*a(9,0))-2*a(7,0)*k(10,0))-2*k(7,0)*a(10,0)); groebnerMatrix(5,77) = (((((((((((2*a(6,0)*m(6,0)+2*a(7,0)*m(7,0))+2*a(8,0)*m(8,0))+2*a(9,0)*m(9,0))+2*a(10,0)*m(10,0))+2*a(11,0)*m(11,0))-2*a(8,0)*m(11,0))-2*m(8,0)*a(11,0))-2*a(6,0)*m(9,0))-2*m(6,0)*a(9,0))-2*a(7,0)*m(10,0))-2*m(7,0)*a(10,0)); groebnerMatrix(5,78) = (((((((((((2*a(6,0)*n(6,0)+2*a(7,0)*n(7,0))+2*a(8,0)*n(8,0))+2*a(9,0)*n(9,0))+2*a(10,0)*n(10,0))+2*a(11,0)*n(11,0))-2*a(8,0)*n(11,0))-2*n(8,0)*a(11,0))-2*a(6,0)*n(9,0))-2*n(6,0)*a(9,0))-2*a(7,0)*n(10,0))-2*n(7,0)*a(10,0)); groebnerMatrix(5,79) = (((((((((-c23w+pow(a(6,0),2))+pow(a(7,0),2))+pow(a(8,0),2))+pow(a(9,0),2))+pow(a(10,0),2))+pow(a(11,0),2))-2*a(6,0)*a(9,0))-2*a(7,0)*a(10,0))-2*a(8,0)*a(11,0)); } opengv/src/absolute_pose/modules/gpnp5/code.cpp0000664016516101651610000012715713344612246020576 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp5::compute( Eigen::Matrix & groebnerMatrix ) { sPolynomial6(groebnerMatrix); sPolynomial7(groebnerMatrix); groebnerRow6_00000_f(groebnerMatrix,7); sPolynomial8(groebnerMatrix); groebnerRow6_00000_f(groebnerMatrix,8); groebnerRow7_00000_f(groebnerMatrix,8); sPolynomial9(groebnerMatrix); groebnerRow6_00000_f(groebnerMatrix,9); groebnerRow7_00000_f(groebnerMatrix,9); groebnerRow8_00000_f(groebnerMatrix,9); sPolynomial10(groebnerMatrix); groebnerRow6_00000_f(groebnerMatrix,10); groebnerRow7_00000_f(groebnerMatrix,10); groebnerRow8_00000_f(groebnerMatrix,10); groebnerRow9_00000_f(groebnerMatrix,10); sPolynomial11(groebnerMatrix); groebnerRow10_00100_f(groebnerMatrix,11); groebnerRow6_01000_f(groebnerMatrix,11); groebnerRow7_01000_f(groebnerMatrix,11); groebnerRow8_01000_f(groebnerMatrix,11); groebnerRow9_01000_f(groebnerMatrix,11); groebnerRow10_01000_f(groebnerMatrix,11); groebnerRow6_10000_f(groebnerMatrix,11); groebnerRow7_10000_f(groebnerMatrix,11); groebnerRow8_10000_f(groebnerMatrix,11); groebnerRow9_10000_f(groebnerMatrix,11); groebnerRow10_10000_f(groebnerMatrix,11); groebnerRow6_00000_f(groebnerMatrix,11); groebnerRow7_00000_f(groebnerMatrix,11); groebnerRow8_00000_f(groebnerMatrix,11); groebnerRow9_00000_f(groebnerMatrix,11); groebnerRow10_00000_f(groebnerMatrix,11); sPolynomial12(groebnerMatrix); groebnerRow9_00100_f(groebnerMatrix,12); groebnerRow10_00100_f(groebnerMatrix,12); groebnerRow5_01000_f(groebnerMatrix,12); groebnerRow6_01000_f(groebnerMatrix,12); groebnerRow7_01000_f(groebnerMatrix,12); groebnerRow8_01000_f(groebnerMatrix,12); groebnerRow9_01000_f(groebnerMatrix,12); groebnerRow10_01000_f(groebnerMatrix,12); groebnerRow11_00000_f(groebnerMatrix,12); groebnerRow5_10000_f(groebnerMatrix,12); groebnerRow6_10000_f(groebnerMatrix,12); groebnerRow7_10000_f(groebnerMatrix,12); groebnerRow8_10000_f(groebnerMatrix,12); groebnerRow9_10000_f(groebnerMatrix,12); groebnerRow10_10000_f(groebnerMatrix,12); groebnerRow5_00000_f(groebnerMatrix,12); groebnerRow6_00000_f(groebnerMatrix,12); groebnerRow7_00000_f(groebnerMatrix,12); groebnerRow8_00000_f(groebnerMatrix,12); groebnerRow9_00000_f(groebnerMatrix,12); groebnerRow10_00000_f(groebnerMatrix,12); sPolynomial13(groebnerMatrix); groebnerRow8_00100_f(groebnerMatrix,13); groebnerRow9_00100_f(groebnerMatrix,13); groebnerRow10_00100_f(groebnerMatrix,13); groebnerRow6_01000_f(groebnerMatrix,13); groebnerRow7_01000_f(groebnerMatrix,13); groebnerRow8_01000_f(groebnerMatrix,13); groebnerRow9_01000_f(groebnerMatrix,13); groebnerRow10_01000_f(groebnerMatrix,13); groebnerRow11_00000_f(groebnerMatrix,13); groebnerRow12_00000_f(groebnerMatrix,13); groebnerRow6_10000_f(groebnerMatrix,13); groebnerRow7_10000_f(groebnerMatrix,13); groebnerRow8_10000_f(groebnerMatrix,13); groebnerRow9_10000_f(groebnerMatrix,13); groebnerRow10_10000_f(groebnerMatrix,13); groebnerRow6_00000_f(groebnerMatrix,13); groebnerRow7_00000_f(groebnerMatrix,13); groebnerRow8_00000_f(groebnerMatrix,13); groebnerRow9_00000_f(groebnerMatrix,13); groebnerRow10_00000_f(groebnerMatrix,13); sPolynomial14(groebnerMatrix); groebnerRow7_00100_f(groebnerMatrix,14); groebnerRow8_00100_f(groebnerMatrix,14); groebnerRow9_00100_f(groebnerMatrix,14); groebnerRow10_00100_f(groebnerMatrix,14); groebnerRow6_01000_f(groebnerMatrix,14); groebnerRow7_01000_f(groebnerMatrix,14); groebnerRow8_01000_f(groebnerMatrix,14); groebnerRow9_01000_f(groebnerMatrix,14); groebnerRow10_01000_f(groebnerMatrix,14); groebnerRow11_00000_f(groebnerMatrix,14); groebnerRow12_00000_f(groebnerMatrix,14); groebnerRow13_00000_f(groebnerMatrix,14); groebnerRow6_10000_f(groebnerMatrix,14); groebnerRow7_10000_f(groebnerMatrix,14); groebnerRow8_10000_f(groebnerMatrix,14); groebnerRow9_10000_f(groebnerMatrix,14); groebnerRow10_10000_f(groebnerMatrix,14); groebnerRow6_00000_f(groebnerMatrix,14); groebnerRow7_00000_f(groebnerMatrix,14); groebnerRow8_00000_f(groebnerMatrix,14); groebnerRow9_00000_f(groebnerMatrix,14); groebnerRow10_00000_f(groebnerMatrix,14); sPolynomial15(groebnerMatrix); groebnerRow7_00100_f(groebnerMatrix,15); groebnerRow8_00100_f(groebnerMatrix,15); groebnerRow9_00100_f(groebnerMatrix,15); groebnerRow10_00100_f(groebnerMatrix,15); groebnerRow5_01000_f(groebnerMatrix,15); groebnerRow6_01000_f(groebnerMatrix,15); groebnerRow7_01000_f(groebnerMatrix,15); groebnerRow8_01000_f(groebnerMatrix,15); groebnerRow9_01000_f(groebnerMatrix,15); groebnerRow10_01000_f(groebnerMatrix,15); groebnerRow11_00000_f(groebnerMatrix,15); groebnerRow12_00000_f(groebnerMatrix,15); groebnerRow13_00000_f(groebnerMatrix,15); groebnerRow14_00000_f(groebnerMatrix,15); groebnerRow5_10000_f(groebnerMatrix,15); groebnerRow6_10000_f(groebnerMatrix,15); groebnerRow7_10000_f(groebnerMatrix,15); groebnerRow8_10000_f(groebnerMatrix,15); groebnerRow9_10000_f(groebnerMatrix,15); groebnerRow10_10000_f(groebnerMatrix,15); groebnerRow5_00000_f(groebnerMatrix,15); groebnerRow6_00000_f(groebnerMatrix,15); groebnerRow7_00000_f(groebnerMatrix,15); groebnerRow8_00000_f(groebnerMatrix,15); groebnerRow9_00000_f(groebnerMatrix,15); groebnerRow10_00000_f(groebnerMatrix,15); sPolynomial16(groebnerMatrix); groebnerRow6_00100_f(groebnerMatrix,16); groebnerRow7_00100_f(groebnerMatrix,16); groebnerRow8_00100_f(groebnerMatrix,16); groebnerRow9_00100_f(groebnerMatrix,16); groebnerRow10_00100_f(groebnerMatrix,16); groebnerRow5_01000_f(groebnerMatrix,16); groebnerRow6_01000_f(groebnerMatrix,16); groebnerRow7_01000_f(groebnerMatrix,16); groebnerRow8_01000_f(groebnerMatrix,16); groebnerRow9_01000_f(groebnerMatrix,16); groebnerRow10_01000_f(groebnerMatrix,16); groebnerRow11_00000_f(groebnerMatrix,16); groebnerRow12_00000_f(groebnerMatrix,16); groebnerRow13_00000_f(groebnerMatrix,16); groebnerRow14_00000_f(groebnerMatrix,16); groebnerRow5_10000_f(groebnerMatrix,16); groebnerRow6_10000_f(groebnerMatrix,16); groebnerRow7_10000_f(groebnerMatrix,16); groebnerRow8_10000_f(groebnerMatrix,16); groebnerRow9_10000_f(groebnerMatrix,16); groebnerRow10_10000_f(groebnerMatrix,16); groebnerRow15_00000_f(groebnerMatrix,16); groebnerRow5_00000_f(groebnerMatrix,16); groebnerRow6_00000_f(groebnerMatrix,16); groebnerRow7_00000_f(groebnerMatrix,16); groebnerRow8_00000_f(groebnerMatrix,16); groebnerRow9_00000_f(groebnerMatrix,16); groebnerRow10_00000_f(groebnerMatrix,16); sPolynomial17(groebnerMatrix); groebnerRow7_00010_f(groebnerMatrix,17); groebnerRow5_00100_f(groebnerMatrix,17); groebnerRow6_00100_f(groebnerMatrix,17); groebnerRow7_00100_f(groebnerMatrix,17); groebnerRow8_00100_f(groebnerMatrix,17); groebnerRow9_00100_f(groebnerMatrix,17); groebnerRow10_00100_f(groebnerMatrix,17); groebnerRow5_01000_f(groebnerMatrix,17); groebnerRow6_01000_f(groebnerMatrix,17); groebnerRow7_01000_f(groebnerMatrix,17); groebnerRow8_01000_f(groebnerMatrix,17); groebnerRow9_01000_f(groebnerMatrix,17); groebnerRow10_01000_f(groebnerMatrix,17); groebnerRow11_00000_f(groebnerMatrix,17); groebnerRow12_00000_f(groebnerMatrix,17); groebnerRow13_00000_f(groebnerMatrix,17); groebnerRow14_00000_f(groebnerMatrix,17); groebnerRow5_10000_f(groebnerMatrix,17); groebnerRow6_10000_f(groebnerMatrix,17); groebnerRow7_10000_f(groebnerMatrix,17); groebnerRow8_10000_f(groebnerMatrix,17); groebnerRow9_10000_f(groebnerMatrix,17); groebnerRow10_10000_f(groebnerMatrix,17); groebnerRow15_00000_f(groebnerMatrix,17); groebnerRow16_00000_f(groebnerMatrix,17); groebnerRow5_00000_f(groebnerMatrix,17); groebnerRow6_00000_f(groebnerMatrix,17); groebnerRow7_00000_f(groebnerMatrix,17); groebnerRow8_00000_f(groebnerMatrix,17); groebnerRow9_00000_f(groebnerMatrix,17); groebnerRow10_00000_f(groebnerMatrix,17); sPolynomial18(groebnerMatrix); groebnerRow6_00010_f(groebnerMatrix,18); groebnerRow7_00010_f(groebnerMatrix,18); groebnerRow5_00100_f(groebnerMatrix,18); groebnerRow6_00100_f(groebnerMatrix,18); groebnerRow7_00100_f(groebnerMatrix,18); groebnerRow8_00100_f(groebnerMatrix,18); groebnerRow9_00100_f(groebnerMatrix,18); groebnerRow10_00100_f(groebnerMatrix,18); groebnerRow5_01000_f(groebnerMatrix,18); groebnerRow6_01000_f(groebnerMatrix,18); groebnerRow7_01000_f(groebnerMatrix,18); groebnerRow8_01000_f(groebnerMatrix,18); groebnerRow9_01000_f(groebnerMatrix,18); groebnerRow10_01000_f(groebnerMatrix,18); groebnerRow11_00000_f(groebnerMatrix,18); groebnerRow12_00000_f(groebnerMatrix,18); groebnerRow13_00000_f(groebnerMatrix,18); groebnerRow14_00000_f(groebnerMatrix,18); groebnerRow5_10000_f(groebnerMatrix,18); groebnerRow6_10000_f(groebnerMatrix,18); groebnerRow7_10000_f(groebnerMatrix,18); groebnerRow8_10000_f(groebnerMatrix,18); groebnerRow9_10000_f(groebnerMatrix,18); groebnerRow10_10000_f(groebnerMatrix,18); groebnerRow15_00000_f(groebnerMatrix,18); groebnerRow16_00000_f(groebnerMatrix,18); groebnerRow17_00000_f(groebnerMatrix,18); groebnerRow5_00000_f(groebnerMatrix,18); groebnerRow6_00000_f(groebnerMatrix,18); groebnerRow7_00000_f(groebnerMatrix,18); groebnerRow8_00000_f(groebnerMatrix,18); groebnerRow9_00000_f(groebnerMatrix,18); groebnerRow10_00000_f(groebnerMatrix,18); sPolynomial19(groebnerMatrix); groebnerRow15_10000_f(groebnerMatrix,19); groebnerRow16_10000_f(groebnerMatrix,19); groebnerRow17_10000_f(groebnerMatrix,19); groebnerRow18_10000_f(groebnerMatrix,19); groebnerRow11_00000_f(groebnerMatrix,19); groebnerRow12_00000_f(groebnerMatrix,19); groebnerRow13_00000_f(groebnerMatrix,19); groebnerRow14_00000_f(groebnerMatrix,19); groebnerRow15_00000_f(groebnerMatrix,19); groebnerRow16_00000_f(groebnerMatrix,19); groebnerRow17_00000_f(groebnerMatrix,19); groebnerRow18_00000_f(groebnerMatrix,19); sPolynomial20(groebnerMatrix); groebnerRow14_10000_f(groebnerMatrix,20); groebnerRow15_10000_f(groebnerMatrix,20); groebnerRow16_10000_f(groebnerMatrix,20); groebnerRow17_10000_f(groebnerMatrix,20); groebnerRow18_10000_f(groebnerMatrix,20); groebnerRow19_00000_f(groebnerMatrix,20); groebnerRow11_00000_f(groebnerMatrix,20); groebnerRow12_00000_f(groebnerMatrix,20); groebnerRow13_00000_f(groebnerMatrix,20); groebnerRow14_00000_f(groebnerMatrix,20); groebnerRow15_00000_f(groebnerMatrix,20); groebnerRow16_00000_f(groebnerMatrix,20); groebnerRow17_00000_f(groebnerMatrix,20); groebnerRow18_00000_f(groebnerMatrix,20); sPolynomial21(groebnerMatrix); groebnerRow14_10000_f(groebnerMatrix,21); groebnerRow8_20000_f(groebnerMatrix,21); groebnerRow9_20000_f(groebnerMatrix,21); groebnerRow10_20000_f(groebnerMatrix,21); groebnerRow15_10000_f(groebnerMatrix,21); groebnerRow16_10000_f(groebnerMatrix,21); groebnerRow17_10000_f(groebnerMatrix,21); groebnerRow18_10000_f(groebnerMatrix,21); groebnerRow19_00000_f(groebnerMatrix,21); groebnerRow20_00000_f(groebnerMatrix,21); groebnerRow8_01000_f(groebnerMatrix,21); groebnerRow9_01000_f(groebnerMatrix,21); groebnerRow10_01000_f(groebnerMatrix,21); groebnerRow11_00000_f(groebnerMatrix,21); groebnerRow12_00000_f(groebnerMatrix,21); groebnerRow13_00000_f(groebnerMatrix,21); groebnerRow14_00000_f(groebnerMatrix,21); groebnerRow8_10000_f(groebnerMatrix,21); groebnerRow9_10000_f(groebnerMatrix,21); groebnerRow10_10000_f(groebnerMatrix,21); groebnerRow15_00000_f(groebnerMatrix,21); groebnerRow16_00000_f(groebnerMatrix,21); groebnerRow17_00000_f(groebnerMatrix,21); groebnerRow18_00000_f(groebnerMatrix,21); groebnerRow8_00000_f(groebnerMatrix,21); groebnerRow9_00000_f(groebnerMatrix,21); groebnerRow10_00000_f(groebnerMatrix,21); sPolynomial22(groebnerMatrix); groebnerRow13_10000_f(groebnerMatrix,22); groebnerRow14_10000_f(groebnerMatrix,22); groebnerRow15_10000_f(groebnerMatrix,22); groebnerRow16_10000_f(groebnerMatrix,22); groebnerRow17_10000_f(groebnerMatrix,22); groebnerRow18_10000_f(groebnerMatrix,22); groebnerRow19_00000_f(groebnerMatrix,22); groebnerRow20_00000_f(groebnerMatrix,22); groebnerRow21_00000_f(groebnerMatrix,22); groebnerRow11_00000_f(groebnerMatrix,22); groebnerRow12_00000_f(groebnerMatrix,22); groebnerRow13_00000_f(groebnerMatrix,22); groebnerRow14_00000_f(groebnerMatrix,22); groebnerRow15_00000_f(groebnerMatrix,22); groebnerRow16_00000_f(groebnerMatrix,22); groebnerRow17_00000_f(groebnerMatrix,22); groebnerRow18_00000_f(groebnerMatrix,22); sPolynomial23(groebnerMatrix); groebnerRow13_10000_f(groebnerMatrix,23); groebnerRow14_10000_f(groebnerMatrix,23); groebnerRow6_20000_f(groebnerMatrix,23); groebnerRow7_20000_f(groebnerMatrix,23); groebnerRow8_20000_f(groebnerMatrix,23); groebnerRow9_20000_f(groebnerMatrix,23); groebnerRow10_20000_f(groebnerMatrix,23); groebnerRow15_10000_f(groebnerMatrix,23); groebnerRow16_10000_f(groebnerMatrix,23); groebnerRow17_10000_f(groebnerMatrix,23); groebnerRow18_10000_f(groebnerMatrix,23); groebnerRow19_00000_f(groebnerMatrix,23); groebnerRow20_00000_f(groebnerMatrix,23); groebnerRow21_00000_f(groebnerMatrix,23); groebnerRow22_00000_f(groebnerMatrix,23); groebnerRow6_01000_f(groebnerMatrix,23); groebnerRow7_01000_f(groebnerMatrix,23); groebnerRow8_01000_f(groebnerMatrix,23); groebnerRow9_01000_f(groebnerMatrix,23); groebnerRow10_01000_f(groebnerMatrix,23); groebnerRow11_00000_f(groebnerMatrix,23); groebnerRow12_00000_f(groebnerMatrix,23); groebnerRow13_00000_f(groebnerMatrix,23); groebnerRow14_00000_f(groebnerMatrix,23); groebnerRow6_10000_f(groebnerMatrix,23); groebnerRow7_10000_f(groebnerMatrix,23); groebnerRow8_10000_f(groebnerMatrix,23); groebnerRow9_10000_f(groebnerMatrix,23); groebnerRow10_10000_f(groebnerMatrix,23); groebnerRow15_00000_f(groebnerMatrix,23); groebnerRow16_00000_f(groebnerMatrix,23); groebnerRow17_00000_f(groebnerMatrix,23); groebnerRow18_00000_f(groebnerMatrix,23); groebnerRow6_00000_f(groebnerMatrix,23); groebnerRow7_00000_f(groebnerMatrix,23); groebnerRow8_00000_f(groebnerMatrix,23); groebnerRow9_00000_f(groebnerMatrix,23); groebnerRow10_00000_f(groebnerMatrix,23); sPolynomial24(groebnerMatrix); groebnerRow12_10000_f(groebnerMatrix,24); groebnerRow13_10000_f(groebnerMatrix,24); groebnerRow14_10000_f(groebnerMatrix,24); groebnerRow15_10000_f(groebnerMatrix,24); groebnerRow16_10000_f(groebnerMatrix,24); groebnerRow17_10000_f(groebnerMatrix,24); groebnerRow18_10000_f(groebnerMatrix,24); groebnerRow19_00000_f(groebnerMatrix,24); groebnerRow20_00000_f(groebnerMatrix,24); groebnerRow21_00000_f(groebnerMatrix,24); groebnerRow22_00000_f(groebnerMatrix,24); groebnerRow23_00000_f(groebnerMatrix,24); groebnerRow11_00000_f(groebnerMatrix,24); groebnerRow12_00000_f(groebnerMatrix,24); groebnerRow13_00000_f(groebnerMatrix,24); groebnerRow14_00000_f(groebnerMatrix,24); groebnerRow15_00000_f(groebnerMatrix,24); groebnerRow16_00000_f(groebnerMatrix,24); groebnerRow17_00000_f(groebnerMatrix,24); groebnerRow18_00000_f(groebnerMatrix,24); sPolynomial25(groebnerMatrix); groebnerRow12_10000_f(groebnerMatrix,25); groebnerRow13_10000_f(groebnerMatrix,25); groebnerRow14_10000_f(groebnerMatrix,25); groebnerRow5_20000_f(groebnerMatrix,25); groebnerRow6_20000_f(groebnerMatrix,25); groebnerRow7_20000_f(groebnerMatrix,25); groebnerRow8_20000_f(groebnerMatrix,25); groebnerRow9_20000_f(groebnerMatrix,25); groebnerRow10_20000_f(groebnerMatrix,25); groebnerRow15_10000_f(groebnerMatrix,25); groebnerRow16_10000_f(groebnerMatrix,25); groebnerRow17_10000_f(groebnerMatrix,25); groebnerRow18_10000_f(groebnerMatrix,25); groebnerRow24_10000_f(groebnerMatrix,25); groebnerRow20_00000_f(groebnerMatrix,25); groebnerRow21_00000_f(groebnerMatrix,25); groebnerRow22_00000_f(groebnerMatrix,25); groebnerRow23_00000_f(groebnerMatrix,25); groebnerRow5_01000_f(groebnerMatrix,25); groebnerRow6_01000_f(groebnerMatrix,25); groebnerRow7_01000_f(groebnerMatrix,25); groebnerRow8_01000_f(groebnerMatrix,25); groebnerRow9_01000_f(groebnerMatrix,25); groebnerRow10_01000_f(groebnerMatrix,25); groebnerRow11_00000_f(groebnerMatrix,25); groebnerRow12_00000_f(groebnerMatrix,25); groebnerRow13_00000_f(groebnerMatrix,25); groebnerRow14_00000_f(groebnerMatrix,25); groebnerRow5_10000_f(groebnerMatrix,25); groebnerRow6_10000_f(groebnerMatrix,25); groebnerRow7_10000_f(groebnerMatrix,25); groebnerRow8_10000_f(groebnerMatrix,25); groebnerRow9_10000_f(groebnerMatrix,25); groebnerRow10_10000_f(groebnerMatrix,25); groebnerRow15_00000_f(groebnerMatrix,25); groebnerRow16_00000_f(groebnerMatrix,25); groebnerRow17_00000_f(groebnerMatrix,25); groebnerRow18_00000_f(groebnerMatrix,25); groebnerRow24_00000_f(groebnerMatrix,25); groebnerRow5_00000_f(groebnerMatrix,25); groebnerRow6_00000_f(groebnerMatrix,25); groebnerRow7_00000_f(groebnerMatrix,25); groebnerRow8_00000_f(groebnerMatrix,25); groebnerRow9_00000_f(groebnerMatrix,25); groebnerRow10_00000_f(groebnerMatrix,25); sPolynomial26(groebnerMatrix); groebnerRow11_10000_f(groebnerMatrix,26); groebnerRow12_10000_f(groebnerMatrix,26); groebnerRow13_10000_f(groebnerMatrix,26); groebnerRow14_10000_f(groebnerMatrix,26); groebnerRow8_20000_f(groebnerMatrix,26); groebnerRow9_20000_f(groebnerMatrix,26); groebnerRow10_20000_f(groebnerMatrix,26); groebnerRow15_10000_f(groebnerMatrix,26); groebnerRow16_10000_f(groebnerMatrix,26); groebnerRow17_10000_f(groebnerMatrix,26); groebnerRow18_10000_f(groebnerMatrix,26); groebnerRow24_10000_f(groebnerMatrix,26); groebnerRow25_10000_f(groebnerMatrix,26); groebnerRow21_00000_f(groebnerMatrix,26); groebnerRow22_00000_f(groebnerMatrix,26); groebnerRow23_00000_f(groebnerMatrix,26); groebnerRow8_01000_f(groebnerMatrix,26); groebnerRow9_01000_f(groebnerMatrix,26); groebnerRow10_01000_f(groebnerMatrix,26); groebnerRow11_00000_f(groebnerMatrix,26); groebnerRow12_00000_f(groebnerMatrix,26); groebnerRow13_00000_f(groebnerMatrix,26); groebnerRow14_00000_f(groebnerMatrix,26); groebnerRow8_10000_f(groebnerMatrix,26); groebnerRow9_10000_f(groebnerMatrix,26); groebnerRow10_10000_f(groebnerMatrix,26); groebnerRow15_00000_f(groebnerMatrix,26); groebnerRow16_00000_f(groebnerMatrix,26); groebnerRow17_00000_f(groebnerMatrix,26); groebnerRow18_00000_f(groebnerMatrix,26); groebnerRow24_00000_f(groebnerMatrix,26); groebnerRow25_00000_f(groebnerMatrix,26); groebnerRow8_00000_f(groebnerMatrix,26); groebnerRow9_00000_f(groebnerMatrix,26); groebnerRow10_00000_f(groebnerMatrix,26); sPolynomial27(groebnerMatrix); groebnerRow10_11000_f(groebnerMatrix,27); groebnerRow11_10000_f(groebnerMatrix,27); groebnerRow12_10000_f(groebnerMatrix,27); groebnerRow13_10000_f(groebnerMatrix,27); groebnerRow14_10000_f(groebnerMatrix,27); groebnerRow8_20000_f(groebnerMatrix,27); groebnerRow9_20000_f(groebnerMatrix,27); groebnerRow10_20000_f(groebnerMatrix,27); groebnerRow15_10000_f(groebnerMatrix,27); groebnerRow16_10000_f(groebnerMatrix,27); groebnerRow17_10000_f(groebnerMatrix,27); groebnerRow18_10000_f(groebnerMatrix,27); groebnerRow24_10000_f(groebnerMatrix,27); groebnerRow25_10000_f(groebnerMatrix,27); groebnerRow26_10000_f(groebnerMatrix,27); groebnerRow22_00000_f(groebnerMatrix,27); groebnerRow23_00000_f(groebnerMatrix,27); groebnerRow8_01000_f(groebnerMatrix,27); groebnerRow9_01000_f(groebnerMatrix,27); groebnerRow10_01000_f(groebnerMatrix,27); groebnerRow11_00000_f(groebnerMatrix,27); groebnerRow12_00000_f(groebnerMatrix,27); groebnerRow13_00000_f(groebnerMatrix,27); groebnerRow14_00000_f(groebnerMatrix,27); groebnerRow8_10000_f(groebnerMatrix,27); groebnerRow9_10000_f(groebnerMatrix,27); groebnerRow10_10000_f(groebnerMatrix,27); groebnerRow15_00000_f(groebnerMatrix,27); groebnerRow16_00000_f(groebnerMatrix,27); groebnerRow17_00000_f(groebnerMatrix,27); groebnerRow18_00000_f(groebnerMatrix,27); groebnerRow24_00000_f(groebnerMatrix,27); groebnerRow25_00000_f(groebnerMatrix,27); groebnerRow26_00000_f(groebnerMatrix,27); groebnerRow8_00000_f(groebnerMatrix,27); groebnerRow9_00000_f(groebnerMatrix,27); groebnerRow10_00000_f(groebnerMatrix,27); sPolynomial28(groebnerMatrix); groebnerRow10_11000_f(groebnerMatrix,28); groebnerRow11_10000_f(groebnerMatrix,28); groebnerRow12_10000_f(groebnerMatrix,28); groebnerRow13_10000_f(groebnerMatrix,28); groebnerRow14_10000_f(groebnerMatrix,28); groebnerRow6_20000_f(groebnerMatrix,28); groebnerRow7_20000_f(groebnerMatrix,28); groebnerRow8_20000_f(groebnerMatrix,28); groebnerRow9_20000_f(groebnerMatrix,28); groebnerRow10_20000_f(groebnerMatrix,28); groebnerRow15_10000_f(groebnerMatrix,28); groebnerRow16_10000_f(groebnerMatrix,28); groebnerRow17_10000_f(groebnerMatrix,28); groebnerRow18_10000_f(groebnerMatrix,28); groebnerRow24_10000_f(groebnerMatrix,28); groebnerRow25_10000_f(groebnerMatrix,28); groebnerRow26_10000_f(groebnerMatrix,28); groebnerRow27_10000_f(groebnerMatrix,28); groebnerRow23_00000_f(groebnerMatrix,28); groebnerRow6_01000_f(groebnerMatrix,28); groebnerRow7_01000_f(groebnerMatrix,28); groebnerRow8_01000_f(groebnerMatrix,28); groebnerRow9_01000_f(groebnerMatrix,28); groebnerRow10_01000_f(groebnerMatrix,28); groebnerRow11_00000_f(groebnerMatrix,28); groebnerRow12_00000_f(groebnerMatrix,28); groebnerRow13_00000_f(groebnerMatrix,28); groebnerRow14_00000_f(groebnerMatrix,28); groebnerRow6_10000_f(groebnerMatrix,28); groebnerRow7_10000_f(groebnerMatrix,28); groebnerRow8_10000_f(groebnerMatrix,28); groebnerRow9_10000_f(groebnerMatrix,28); groebnerRow10_10000_f(groebnerMatrix,28); groebnerRow15_00000_f(groebnerMatrix,28); groebnerRow16_00000_f(groebnerMatrix,28); groebnerRow17_00000_f(groebnerMatrix,28); groebnerRow18_00000_f(groebnerMatrix,28); groebnerRow24_00000_f(groebnerMatrix,28); groebnerRow25_00000_f(groebnerMatrix,28); groebnerRow26_00000_f(groebnerMatrix,28); groebnerRow27_00000_f(groebnerMatrix,28); groebnerRow6_00000_f(groebnerMatrix,28); groebnerRow7_00000_f(groebnerMatrix,28); groebnerRow8_00000_f(groebnerMatrix,28); groebnerRow9_00000_f(groebnerMatrix,28); groebnerRow10_00000_f(groebnerMatrix,28); sPolynomial29(groebnerMatrix); groebnerRow9_11000_f(groebnerMatrix,29); groebnerRow10_11000_f(groebnerMatrix,29); groebnerRow11_10000_f(groebnerMatrix,29); groebnerRow12_10000_f(groebnerMatrix,29); groebnerRow13_10000_f(groebnerMatrix,29); groebnerRow14_10000_f(groebnerMatrix,29); groebnerRow8_20000_f(groebnerMatrix,29); groebnerRow9_20000_f(groebnerMatrix,29); groebnerRow10_20000_f(groebnerMatrix,29); groebnerRow15_10000_f(groebnerMatrix,29); groebnerRow16_10000_f(groebnerMatrix,29); groebnerRow17_10000_f(groebnerMatrix,29); groebnerRow18_10000_f(groebnerMatrix,29); groebnerRow24_10000_f(groebnerMatrix,29); groebnerRow25_10000_f(groebnerMatrix,29); groebnerRow26_10000_f(groebnerMatrix,29); groebnerRow27_10000_f(groebnerMatrix,29); groebnerRow28_10000_f(groebnerMatrix,29); groebnerRow8_01000_f(groebnerMatrix,29); groebnerRow9_01000_f(groebnerMatrix,29); groebnerRow10_01000_f(groebnerMatrix,29); groebnerRow11_00000_f(groebnerMatrix,29); groebnerRow12_00000_f(groebnerMatrix,29); groebnerRow13_00000_f(groebnerMatrix,29); groebnerRow14_00000_f(groebnerMatrix,29); groebnerRow8_10000_f(groebnerMatrix,29); groebnerRow9_10000_f(groebnerMatrix,29); groebnerRow10_10000_f(groebnerMatrix,29); groebnerRow15_00000_f(groebnerMatrix,29); groebnerRow16_00000_f(groebnerMatrix,29); groebnerRow17_00000_f(groebnerMatrix,29); groebnerRow18_00000_f(groebnerMatrix,29); groebnerRow24_00000_f(groebnerMatrix,29); groebnerRow25_00000_f(groebnerMatrix,29); groebnerRow26_00000_f(groebnerMatrix,29); groebnerRow27_00000_f(groebnerMatrix,29); groebnerRow28_00000_f(groebnerMatrix,29); groebnerRow8_00000_f(groebnerMatrix,29); groebnerRow9_00000_f(groebnerMatrix,29); groebnerRow10_00000_f(groebnerMatrix,29); sPolynomial30(groebnerMatrix); groebnerRow9_11000_f(groebnerMatrix,30); groebnerRow10_11000_f(groebnerMatrix,30); groebnerRow18_00001_f(groebnerMatrix,30); groebnerRow12_10000_f(groebnerMatrix,30); groebnerRow13_10000_f(groebnerMatrix,30); groebnerRow14_10000_f(groebnerMatrix,30); groebnerRow5_20000_f(groebnerMatrix,30); groebnerRow6_20000_f(groebnerMatrix,30); groebnerRow7_20000_f(groebnerMatrix,30); groebnerRow8_20000_f(groebnerMatrix,30); groebnerRow9_20000_f(groebnerMatrix,30); groebnerRow10_20000_f(groebnerMatrix,30); groebnerRow24_01000_f(groebnerMatrix,30); groebnerRow16_10000_f(groebnerMatrix,30); groebnerRow17_10000_f(groebnerMatrix,30); groebnerRow18_10000_f(groebnerMatrix,30); groebnerRow24_10000_f(groebnerMatrix,30); groebnerRow25_10000_f(groebnerMatrix,30); groebnerRow26_10000_f(groebnerMatrix,30); groebnerRow27_10000_f(groebnerMatrix,30); groebnerRow28_10000_f(groebnerMatrix,30); groebnerRow5_01000_f(groebnerMatrix,30); groebnerRow6_01000_f(groebnerMatrix,30); groebnerRow7_01000_f(groebnerMatrix,30); groebnerRow8_01000_f(groebnerMatrix,30); groebnerRow9_01000_f(groebnerMatrix,30); groebnerRow10_01000_f(groebnerMatrix,30); groebnerRow29_01000_f(groebnerMatrix,30); groebnerRow12_00000_f(groebnerMatrix,30); groebnerRow13_00000_f(groebnerMatrix,30); groebnerRow14_00000_f(groebnerMatrix,30); groebnerRow5_10000_f(groebnerMatrix,30); groebnerRow6_10000_f(groebnerMatrix,30); groebnerRow7_10000_f(groebnerMatrix,30); groebnerRow8_10000_f(groebnerMatrix,30); groebnerRow9_10000_f(groebnerMatrix,30); groebnerRow10_10000_f(groebnerMatrix,30); groebnerRow29_10000_f(groebnerMatrix,30); groebnerRow16_00000_f(groebnerMatrix,30); groebnerRow17_00000_f(groebnerMatrix,30); groebnerRow18_00000_f(groebnerMatrix,30); groebnerRow24_00000_f(groebnerMatrix,30); groebnerRow25_00000_f(groebnerMatrix,30); groebnerRow26_00000_f(groebnerMatrix,30); groebnerRow27_00000_f(groebnerMatrix,30); groebnerRow28_00000_f(groebnerMatrix,30); groebnerRow5_00000_f(groebnerMatrix,30); groebnerRow6_00000_f(groebnerMatrix,30); groebnerRow7_00000_f(groebnerMatrix,30); groebnerRow8_00000_f(groebnerMatrix,30); groebnerRow9_00000_f(groebnerMatrix,30); groebnerRow10_00000_f(groebnerMatrix,30); groebnerRow29_00000_f(groebnerMatrix,30); sPolynomial31(groebnerMatrix); groebnerRow14_01000_f(groebnerMatrix,31); groebnerRow8_11000_f(groebnerMatrix,31); groebnerRow9_11000_f(groebnerMatrix,31); groebnerRow10_11000_f(groebnerMatrix,31); groebnerRow18_00001_f(groebnerMatrix,31); groebnerRow18_00010_f(groebnerMatrix,31); groebnerRow13_10000_f(groebnerMatrix,31); groebnerRow14_10000_f(groebnerMatrix,31); groebnerRow5_20000_f(groebnerMatrix,31); groebnerRow6_20000_f(groebnerMatrix,31); groebnerRow7_20000_f(groebnerMatrix,31); groebnerRow8_20000_f(groebnerMatrix,31); groebnerRow9_20000_f(groebnerMatrix,31); groebnerRow10_20000_f(groebnerMatrix,31); groebnerRow24_01000_f(groebnerMatrix,31); groebnerRow25_01000_f(groebnerMatrix,31); groebnerRow17_10000_f(groebnerMatrix,31); groebnerRow18_10000_f(groebnerMatrix,31); groebnerRow24_10000_f(groebnerMatrix,31); groebnerRow25_10000_f(groebnerMatrix,31); groebnerRow26_10000_f(groebnerMatrix,31); groebnerRow27_10000_f(groebnerMatrix,31); groebnerRow28_10000_f(groebnerMatrix,31); groebnerRow5_01000_f(groebnerMatrix,31); groebnerRow6_01000_f(groebnerMatrix,31); groebnerRow7_01000_f(groebnerMatrix,31); groebnerRow8_01000_f(groebnerMatrix,31); groebnerRow9_01000_f(groebnerMatrix,31); groebnerRow10_01000_f(groebnerMatrix,31); groebnerRow29_01000_f(groebnerMatrix,31); groebnerRow30_01000_f(groebnerMatrix,31); groebnerRow13_00000_f(groebnerMatrix,31); groebnerRow14_00000_f(groebnerMatrix,31); groebnerRow5_10000_f(groebnerMatrix,31); groebnerRow6_10000_f(groebnerMatrix,31); groebnerRow7_10000_f(groebnerMatrix,31); groebnerRow8_10000_f(groebnerMatrix,31); groebnerRow9_10000_f(groebnerMatrix,31); groebnerRow10_10000_f(groebnerMatrix,31); groebnerRow29_10000_f(groebnerMatrix,31); groebnerRow30_10000_f(groebnerMatrix,31); groebnerRow17_00000_f(groebnerMatrix,31); groebnerRow18_00000_f(groebnerMatrix,31); groebnerRow24_00000_f(groebnerMatrix,31); groebnerRow25_00000_f(groebnerMatrix,31); groebnerRow26_00000_f(groebnerMatrix,31); groebnerRow27_00000_f(groebnerMatrix,31); groebnerRow28_00000_f(groebnerMatrix,31); groebnerRow5_00000_f(groebnerMatrix,31); groebnerRow6_00000_f(groebnerMatrix,31); groebnerRow7_00000_f(groebnerMatrix,31); groebnerRow8_00000_f(groebnerMatrix,31); groebnerRow9_00000_f(groebnerMatrix,31); groebnerRow10_00000_f(groebnerMatrix,31); groebnerRow29_00000_f(groebnerMatrix,31); groebnerRow30_00000_f(groebnerMatrix,31); sPolynomial32(groebnerMatrix); groebnerRow14_00100_f(groebnerMatrix,32); groebnerRow14_01000_f(groebnerMatrix,32); groebnerRow6_11000_f(groebnerMatrix,32); groebnerRow7_11000_f(groebnerMatrix,32); groebnerRow8_11000_f(groebnerMatrix,32); groebnerRow9_11000_f(groebnerMatrix,32); groebnerRow10_11000_f(groebnerMatrix,32); groebnerRow18_00001_f(groebnerMatrix,32); groebnerRow18_00010_f(groebnerMatrix,32); groebnerRow18_00100_f(groebnerMatrix,32); groebnerRow14_10000_f(groebnerMatrix,32); groebnerRow5_20000_f(groebnerMatrix,32); groebnerRow6_20000_f(groebnerMatrix,32); groebnerRow7_20000_f(groebnerMatrix,32); groebnerRow8_20000_f(groebnerMatrix,32); groebnerRow9_20000_f(groebnerMatrix,32); groebnerRow10_20000_f(groebnerMatrix,32); groebnerRow24_01000_f(groebnerMatrix,32); groebnerRow25_01000_f(groebnerMatrix,32); groebnerRow26_01000_f(groebnerMatrix,32); groebnerRow18_10000_f(groebnerMatrix,32); groebnerRow24_10000_f(groebnerMatrix,32); groebnerRow25_10000_f(groebnerMatrix,32); groebnerRow26_10000_f(groebnerMatrix,32); groebnerRow27_10000_f(groebnerMatrix,32); groebnerRow28_10000_f(groebnerMatrix,32); groebnerRow5_01000_f(groebnerMatrix,32); groebnerRow6_01000_f(groebnerMatrix,32); groebnerRow7_01000_f(groebnerMatrix,32); groebnerRow8_01000_f(groebnerMatrix,32); groebnerRow9_01000_f(groebnerMatrix,32); groebnerRow10_01000_f(groebnerMatrix,32); groebnerRow29_01000_f(groebnerMatrix,32); groebnerRow30_01000_f(groebnerMatrix,32); groebnerRow31_01000_f(groebnerMatrix,32); groebnerRow14_00000_f(groebnerMatrix,32); groebnerRow5_10000_f(groebnerMatrix,32); groebnerRow6_10000_f(groebnerMatrix,32); groebnerRow7_10000_f(groebnerMatrix,32); groebnerRow8_10000_f(groebnerMatrix,32); groebnerRow9_10000_f(groebnerMatrix,32); groebnerRow10_10000_f(groebnerMatrix,32); groebnerRow29_10000_f(groebnerMatrix,32); groebnerRow30_10000_f(groebnerMatrix,32); groebnerRow31_10000_f(groebnerMatrix,32); groebnerRow18_00000_f(groebnerMatrix,32); groebnerRow24_00000_f(groebnerMatrix,32); groebnerRow25_00000_f(groebnerMatrix,32); groebnerRow26_00000_f(groebnerMatrix,32); groebnerRow27_00000_f(groebnerMatrix,32); groebnerRow28_00000_f(groebnerMatrix,32); groebnerRow5_00000_f(groebnerMatrix,32); groebnerRow6_00000_f(groebnerMatrix,32); groebnerRow7_00000_f(groebnerMatrix,32); groebnerRow8_00000_f(groebnerMatrix,32); groebnerRow9_00000_f(groebnerMatrix,32); groebnerRow10_00000_f(groebnerMatrix,32); groebnerRow29_00000_f(groebnerMatrix,32); groebnerRow30_00000_f(groebnerMatrix,32); groebnerRow31_00000_f(groebnerMatrix,32); sPolynomial33(groebnerMatrix); groebnerRow24_00000_f(groebnerMatrix,33); groebnerRow25_00000_f(groebnerMatrix,33); groebnerRow26_00000_f(groebnerMatrix,33); groebnerRow27_00000_f(groebnerMatrix,33); groebnerRow28_00000_f(groebnerMatrix,33); groebnerRow29_00000_f(groebnerMatrix,33); groebnerRow30_00000_f(groebnerMatrix,33); groebnerRow31_00000_f(groebnerMatrix,33); groebnerRow32_00000_f(groebnerMatrix,33); sPolynomial34(groebnerMatrix); groebnerRow32_10000_f(groebnerMatrix,34); groebnerRow33_10000_f(groebnerMatrix,34); groebnerRow25_00000_f(groebnerMatrix,34); groebnerRow26_00000_f(groebnerMatrix,34); groebnerRow27_00000_f(groebnerMatrix,34); groebnerRow28_00000_f(groebnerMatrix,34); groebnerRow29_00000_f(groebnerMatrix,34); groebnerRow30_00000_f(groebnerMatrix,34); groebnerRow31_00000_f(groebnerMatrix,34); groebnerRow32_00000_f(groebnerMatrix,34); groebnerRow33_00000_f(groebnerMatrix,34); sPolynomial35(groebnerMatrix); groebnerRow31_10000_f(groebnerMatrix,35); groebnerRow32_10000_f(groebnerMatrix,35); groebnerRow33_10000_f(groebnerMatrix,35); groebnerRow34_10000_f(groebnerMatrix,35); groebnerRow26_00000_f(groebnerMatrix,35); groebnerRow27_00000_f(groebnerMatrix,35); groebnerRow28_00000_f(groebnerMatrix,35); groebnerRow29_00000_f(groebnerMatrix,35); groebnerRow30_00000_f(groebnerMatrix,35); groebnerRow31_00000_f(groebnerMatrix,35); groebnerRow32_00000_f(groebnerMatrix,35); groebnerRow33_00000_f(groebnerMatrix,35); groebnerRow34_00000_f(groebnerMatrix,35); sPolynomial36(groebnerMatrix); groebnerRow30_10000_f(groebnerMatrix,36); groebnerRow31_10000_f(groebnerMatrix,36); groebnerRow32_10000_f(groebnerMatrix,36); groebnerRow33_10000_f(groebnerMatrix,36); groebnerRow34_10000_f(groebnerMatrix,36); groebnerRow35_10000_f(groebnerMatrix,36); groebnerRow27_00000_f(groebnerMatrix,36); groebnerRow28_00000_f(groebnerMatrix,36); groebnerRow29_00000_f(groebnerMatrix,36); groebnerRow30_00000_f(groebnerMatrix,36); groebnerRow31_00000_f(groebnerMatrix,36); groebnerRow32_00000_f(groebnerMatrix,36); groebnerRow33_00000_f(groebnerMatrix,36); groebnerRow34_00000_f(groebnerMatrix,36); groebnerRow35_00000_f(groebnerMatrix,36); sPolynomial37(groebnerMatrix); groebnerRow29_10000_f(groebnerMatrix,37); groebnerRow30_10000_f(groebnerMatrix,37); groebnerRow31_10000_f(groebnerMatrix,37); groebnerRow32_10000_f(groebnerMatrix,37); groebnerRow33_10000_f(groebnerMatrix,37); groebnerRow34_10000_f(groebnerMatrix,37); groebnerRow35_10000_f(groebnerMatrix,37); groebnerRow36_10000_f(groebnerMatrix,37); groebnerRow28_00000_f(groebnerMatrix,37); groebnerRow29_00000_f(groebnerMatrix,37); groebnerRow30_00000_f(groebnerMatrix,37); groebnerRow31_00000_f(groebnerMatrix,37); groebnerRow32_00000_f(groebnerMatrix,37); groebnerRow33_00000_f(groebnerMatrix,37); groebnerRow34_00000_f(groebnerMatrix,37); groebnerRow35_00000_f(groebnerMatrix,37); groebnerRow36_00000_f(groebnerMatrix,37); sPolynomial38(groebnerMatrix); groebnerRow32_01000_f(groebnerMatrix,38); groebnerRow29_10000_f(groebnerMatrix,38); groebnerRow30_10000_f(groebnerMatrix,38); groebnerRow31_10000_f(groebnerMatrix,38); groebnerRow32_10000_f(groebnerMatrix,38); groebnerRow33_10000_f(groebnerMatrix,38); groebnerRow34_10000_f(groebnerMatrix,38); groebnerRow35_10000_f(groebnerMatrix,38); groebnerRow36_10000_f(groebnerMatrix,38); groebnerRow37_10000_f(groebnerMatrix,38); groebnerRow29_00000_f(groebnerMatrix,38); groebnerRow30_00000_f(groebnerMatrix,38); groebnerRow31_00000_f(groebnerMatrix,38); groebnerRow32_00000_f(groebnerMatrix,38); groebnerRow33_00000_f(groebnerMatrix,38); groebnerRow34_00000_f(groebnerMatrix,38); groebnerRow35_00000_f(groebnerMatrix,38); groebnerRow36_00000_f(groebnerMatrix,38); groebnerRow37_00000_f(groebnerMatrix,38); sPolynomial39(groebnerMatrix); groebnerRow32_01000_f(groebnerMatrix,39); groebnerRow35_00001_f(groebnerMatrix,39); groebnerRow9_10000_f(groebnerMatrix,39); groebnerRow10_10000_f(groebnerMatrix,39); groebnerRow36_00001_f(groebnerMatrix,39); groebnerRow30_10000_f(groebnerMatrix,39); groebnerRow31_10000_f(groebnerMatrix,39); groebnerRow32_10000_f(groebnerMatrix,39); groebnerRow37_00001_f(groebnerMatrix,39); groebnerRow34_10000_f(groebnerMatrix,39); groebnerRow35_10000_f(groebnerMatrix,39); groebnerRow36_10000_f(groebnerMatrix,39); groebnerRow37_10000_f(groebnerMatrix,39); groebnerRow38_00001_f(groebnerMatrix,39); groebnerRow38_00010_f(groebnerMatrix,39); groebnerRow7_00000_f(groebnerMatrix,39); groebnerRow38_00100_f(groebnerMatrix,39); groebnerRow9_00000_f(groebnerMatrix,39); groebnerRow10_00000_f(groebnerMatrix,39); groebnerRow38_01000_f(groebnerMatrix,39); groebnerRow30_00000_f(groebnerMatrix,39); groebnerRow31_00000_f(groebnerMatrix,39); groebnerRow32_00000_f(groebnerMatrix,39); groebnerRow38_10000_f(groebnerMatrix,39); groebnerRow34_00000_f(groebnerMatrix,39); groebnerRow35_00000_f(groebnerMatrix,39); groebnerRow36_00000_f(groebnerMatrix,39); groebnerRow37_00000_f(groebnerMatrix,39); groebnerRow38_00000_f(groebnerMatrix,39); sPolynomial40(groebnerMatrix); groebnerRow31_01000_f(groebnerMatrix,40); groebnerRow32_01000_f(groebnerMatrix,40); groebnerRow36_00001_f(groebnerMatrix,40); groebnerRow36_00010_f(groebnerMatrix,40); groebnerRow31_10000_f(groebnerMatrix,40); groebnerRow32_10000_f(groebnerMatrix,40); groebnerRow37_00001_f(groebnerMatrix,40); groebnerRow37_00010_f(groebnerMatrix,40); groebnerRow35_10000_f(groebnerMatrix,40); groebnerRow36_10000_f(groebnerMatrix,40); groebnerRow37_10000_f(groebnerMatrix,40); groebnerRow38_00001_f(groebnerMatrix,40); groebnerRow38_00010_f(groebnerMatrix,40); groebnerRow39_00010_f(groebnerMatrix,40); groebnerRow38_00100_f(groebnerMatrix,40); groebnerRow39_00100_f(groebnerMatrix,40); groebnerRow10_00000_f(groebnerMatrix,40); groebnerRow38_01000_f(groebnerMatrix,40); groebnerRow39_01000_f(groebnerMatrix,40); groebnerRow31_00000_f(groebnerMatrix,40); groebnerRow32_00000_f(groebnerMatrix,40); groebnerRow38_10000_f(groebnerMatrix,40); groebnerRow39_10000_f(groebnerMatrix,40); groebnerRow35_00000_f(groebnerMatrix,40); groebnerRow36_00000_f(groebnerMatrix,40); groebnerRow37_00000_f(groebnerMatrix,40); groebnerRow38_00000_f(groebnerMatrix,40); groebnerRow39_00000_f(groebnerMatrix,40); sPolynomial41(groebnerMatrix); groebnerRow32_00100_f(groebnerMatrix,41); groebnerRow32_01000_f(groebnerMatrix,41); groebnerRow38_10010_f(groebnerMatrix,41); groebnerRow39_10010_f(groebnerMatrix,41); groebnerRow38_10100_f(groebnerMatrix,41); groebnerRow39_10100_f(groebnerMatrix,41); groebnerRow40_10100_f(groebnerMatrix,41); groebnerRow36_00001_f(groebnerMatrix,41); groebnerRow36_00010_f(groebnerMatrix,41); groebnerRow36_00100_f(groebnerMatrix,41); groebnerRow32_10000_f(groebnerMatrix,41); groebnerRow37_00001_f(groebnerMatrix,41); groebnerRow37_00010_f(groebnerMatrix,41); groebnerRow37_00100_f(groebnerMatrix,41); groebnerRow36_10000_f(groebnerMatrix,41); groebnerRow37_10000_f(groebnerMatrix,41); groebnerRow38_00001_f(groebnerMatrix,41); groebnerRow38_00010_f(groebnerMatrix,41); groebnerRow39_00010_f(groebnerMatrix,41); groebnerRow38_00100_f(groebnerMatrix,41); groebnerRow39_00100_f(groebnerMatrix,41); groebnerRow40_00100_f(groebnerMatrix,41); groebnerRow38_01000_f(groebnerMatrix,41); groebnerRow39_01000_f(groebnerMatrix,41); groebnerRow40_01000_f(groebnerMatrix,41); groebnerRow32_00000_f(groebnerMatrix,41); groebnerRow38_10000_f(groebnerMatrix,41); groebnerRow39_10000_f(groebnerMatrix,41); groebnerRow40_10000_f(groebnerMatrix,41); groebnerRow36_00000_f(groebnerMatrix,41); groebnerRow37_00000_f(groebnerMatrix,41); groebnerRow38_00000_f(groebnerMatrix,41); groebnerRow39_00000_f(groebnerMatrix,41); groebnerRow40_00000_f(groebnerMatrix,41); sPolynomial42(groebnerMatrix); groebnerRow39_02000_f(groebnerMatrix,42); groebnerRow40_02000_f(groebnerMatrix,42); groebnerRow41_02000_f(groebnerMatrix,42); groebnerRow38_11000_f(groebnerMatrix,42); groebnerRow39_11000_f(groebnerMatrix,42); groebnerRow40_11000_f(groebnerMatrix,42); groebnerRow41_11000_f(groebnerMatrix,42); groebnerRow37_00001_f(groebnerMatrix,42); groebnerRow37_00010_f(groebnerMatrix,42); groebnerRow37_00100_f(groebnerMatrix,42); groebnerRow37_01000_f(groebnerMatrix,42); groebnerRow37_10000_f(groebnerMatrix,42); groebnerRow38_00001_f(groebnerMatrix,42); groebnerRow38_00010_f(groebnerMatrix,42); groebnerRow39_00010_f(groebnerMatrix,42); groebnerRow38_00100_f(groebnerMatrix,42); groebnerRow39_00100_f(groebnerMatrix,42); groebnerRow40_00100_f(groebnerMatrix,42); groebnerRow38_01000_f(groebnerMatrix,42); groebnerRow39_01000_f(groebnerMatrix,42); groebnerRow40_01000_f(groebnerMatrix,42); groebnerRow41_01000_f(groebnerMatrix,42); groebnerRow38_10000_f(groebnerMatrix,42); groebnerRow39_10000_f(groebnerMatrix,42); groebnerRow40_10000_f(groebnerMatrix,42); groebnerRow41_10000_f(groebnerMatrix,42); groebnerRow37_00000_f(groebnerMatrix,42); groebnerRow38_00000_f(groebnerMatrix,42); groebnerRow39_00000_f(groebnerMatrix,42); groebnerRow40_00000_f(groebnerMatrix,42); groebnerRow41_00000_f(groebnerMatrix,42); sPolynomial43(groebnerMatrix); groebnerRow38_11000_f(groebnerMatrix,43); groebnerRow39_11000_f(groebnerMatrix,43); groebnerRow40_11000_f(groebnerMatrix,43); groebnerRow41_11000_f(groebnerMatrix,43); groebnerRow38_20000_f(groebnerMatrix,43); groebnerRow39_20000_f(groebnerMatrix,43); groebnerRow40_20000_f(groebnerMatrix,43); groebnerRow41_20000_f(groebnerMatrix,43); groebnerRow42_20000_f(groebnerMatrix,43); groebnerRow38_01000_f(groebnerMatrix,43); groebnerRow39_01000_f(groebnerMatrix,43); groebnerRow40_01000_f(groebnerMatrix,43); groebnerRow41_01000_f(groebnerMatrix,43); groebnerRow38_10000_f(groebnerMatrix,43); groebnerRow39_10000_f(groebnerMatrix,43); groebnerRow40_10000_f(groebnerMatrix,43); groebnerRow41_10000_f(groebnerMatrix,43); groebnerRow42_10000_f(groebnerMatrix,43); groebnerRow38_00000_f(groebnerMatrix,43); groebnerRow39_00000_f(groebnerMatrix,43); groebnerRow40_00000_f(groebnerMatrix,43); groebnerRow41_00000_f(groebnerMatrix,43); groebnerRow42_00000_f(groebnerMatrix,43); } opengv/src/absolute_pose/modules/gpnp3/0000775016516101651610000000000013344612246017141 5ustar dimadimaopengv/src/absolute_pose/modules/gpnp3/reductors.cpp0000664016516101651610000003670513344612246021672 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp3::groebnerRow4_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,9) / groebnerMatrix(4,9); groebnerMatrix(targetRow,9) = 0.0; groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(4,10); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(4,11); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(4,12); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(4,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(4,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(4,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(4,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(4,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow5_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,10) / groebnerMatrix(5,10); groebnerMatrix(targetRow,10) = 0.0; groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(5,11); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(5,12); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(5,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(5,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(5,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(5,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(5,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow5_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,4) / groebnerMatrix(5,10); groebnerMatrix(targetRow,4) = 0.0; groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(5,11); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(5,12); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(5,13); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(5,14); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(5,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(5,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(5,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow6_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,5) / groebnerMatrix(6,11); groebnerMatrix(targetRow,5) = 0.0; groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(6,12); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(6,13); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(6,14); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(6,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(6,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(6,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow6_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,11) / groebnerMatrix(6,11); groebnerMatrix(targetRow,11) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(6,12); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(6,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(6,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(6,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(6,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(6,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow4_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,3) / groebnerMatrix(4,9); groebnerMatrix(targetRow,3) = 0.0; groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(4,10); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(4,11); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(4,12); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(4,13); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(4,14); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(4,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(4,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(4,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow7_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,6) / groebnerMatrix(7,6); groebnerMatrix(targetRow,6) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(7,7); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(7,12); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(7,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(7,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(7,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(7,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(7,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow3_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,8) / groebnerMatrix(3,8); groebnerMatrix(targetRow,8) = 0.0; groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(3,9); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(3,10); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(3,11); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(3,12); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(3,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(3,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(3,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(3,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(3,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow5_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(5,10); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(5,11); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(5,12); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(5,13); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(5,14); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(5,15); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(5,16); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(5,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow3_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,2) / groebnerMatrix(3,8); groebnerMatrix(targetRow,2) = 0.0; groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(3,9); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(3,10); groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(3,11); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(3,12); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(3,13); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(3,14); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(3,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(3,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(3,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow8_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,7) / groebnerMatrix(8,7); groebnerMatrix(targetRow,7) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(8,12); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(8,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(8,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(8,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(8,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(8,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow4_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,0) / groebnerMatrix(4,9); groebnerMatrix(targetRow,0) = 0.0; groebnerMatrix(targetRow,1) -= factor * groebnerMatrix(4,10); groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(4,11); groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(4,12); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(4,13); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(4,14); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(4,15); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(4,16); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(4,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow9_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,6) / groebnerMatrix(9,12); groebnerMatrix(targetRow,6) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(9,13); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(9,14); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(9,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(9,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(9,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow9_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,12) / groebnerMatrix(9,12); groebnerMatrix(targetRow,12) = 0.0; groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(9,13); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(9,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(9,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(9,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(9,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow10_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,13) / groebnerMatrix(10,13); groebnerMatrix(targetRow,13) = 0.0; groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(10,14); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(10,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(10,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(10,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow10_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,7) / groebnerMatrix(10,13); groebnerMatrix(targetRow,7) = 0.0; groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(10,14); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(10,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(10,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(10,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow11_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,11) / groebnerMatrix(11,14); groebnerMatrix(targetRow,11) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(11,15); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(11,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(11,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow11_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,14) / groebnerMatrix(11,14); groebnerMatrix(targetRow,14) = 0.0; groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(11,15); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(11,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(11,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow11_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,9) / groebnerMatrix(11,14); groebnerMatrix(targetRow,9) = 0.0; groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(11,15); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(11,16); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(11,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow12_010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,10) / groebnerMatrix(12,15); groebnerMatrix(targetRow,10) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(12,16); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(12,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow12_100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,12) / groebnerMatrix(12,15); groebnerMatrix(targetRow,12) = 0.0; groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(12,16); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(12,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow12_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,15) / groebnerMatrix(12,15); groebnerMatrix(targetRow,15) = 0.0; groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(12,16); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(12,17); } void opengv::absolute_pose::modules::gpnp3::groebnerRow13_000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,16) / groebnerMatrix(13,16); groebnerMatrix(targetRow,16) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(13,17); } opengv/src/absolute_pose/modules/gpnp3/spolynomials.cpp0000664016516101651610000003125713344612246022406 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp3::sPolynomial4( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(4,9) = (groebnerMatrix(0,9)/(groebnerMatrix(0,8))-groebnerMatrix(1,9)/(groebnerMatrix(1,8))); groebnerMatrix(4,10) = (groebnerMatrix(0,10)/(groebnerMatrix(0,8))-groebnerMatrix(1,10)/(groebnerMatrix(1,8))); groebnerMatrix(4,11) = (groebnerMatrix(0,11)/(groebnerMatrix(0,8))-groebnerMatrix(1,11)/(groebnerMatrix(1,8))); groebnerMatrix(4,12) = (groebnerMatrix(0,12)/(groebnerMatrix(0,8))-groebnerMatrix(1,12)/(groebnerMatrix(1,8))); groebnerMatrix(4,13) = (groebnerMatrix(0,13)/(groebnerMatrix(0,8))-groebnerMatrix(1,13)/(groebnerMatrix(1,8))); groebnerMatrix(4,14) = (groebnerMatrix(0,14)/(groebnerMatrix(0,8))-groebnerMatrix(1,14)/(groebnerMatrix(1,8))); groebnerMatrix(4,15) = (groebnerMatrix(0,15)/(groebnerMatrix(0,8))-groebnerMatrix(1,15)/(groebnerMatrix(1,8))); groebnerMatrix(4,16) = (groebnerMatrix(0,16)/(groebnerMatrix(0,8))-groebnerMatrix(1,16)/(groebnerMatrix(1,8))); groebnerMatrix(4,17) = (groebnerMatrix(0,17)/(groebnerMatrix(0,8))-groebnerMatrix(1,17)/(groebnerMatrix(1,8))); } void opengv::absolute_pose::modules::gpnp3::sPolynomial5( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(5,9) = (groebnerMatrix(1,9)/(groebnerMatrix(1,8))-groebnerMatrix(2,9)/(groebnerMatrix(2,8))); groebnerMatrix(5,10) = (groebnerMatrix(1,10)/(groebnerMatrix(1,8))-groebnerMatrix(2,10)/(groebnerMatrix(2,8))); groebnerMatrix(5,11) = (groebnerMatrix(1,11)/(groebnerMatrix(1,8))-groebnerMatrix(2,11)/(groebnerMatrix(2,8))); groebnerMatrix(5,12) = (groebnerMatrix(1,12)/(groebnerMatrix(1,8))-groebnerMatrix(2,12)/(groebnerMatrix(2,8))); groebnerMatrix(5,13) = (groebnerMatrix(1,13)/(groebnerMatrix(1,8))-groebnerMatrix(2,13)/(groebnerMatrix(2,8))); groebnerMatrix(5,14) = (groebnerMatrix(1,14)/(groebnerMatrix(1,8))-groebnerMatrix(2,14)/(groebnerMatrix(2,8))); groebnerMatrix(5,15) = (groebnerMatrix(1,15)/(groebnerMatrix(1,8))-groebnerMatrix(2,15)/(groebnerMatrix(2,8))); groebnerMatrix(5,16) = (groebnerMatrix(1,16)/(groebnerMatrix(1,8))-groebnerMatrix(2,16)/(groebnerMatrix(2,8))); groebnerMatrix(5,17) = (groebnerMatrix(1,17)/(groebnerMatrix(1,8))-groebnerMatrix(2,17)/(groebnerMatrix(2,8))); } void opengv::absolute_pose::modules::gpnp3::sPolynomial6( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(6,9) = (groebnerMatrix(2,9)/(groebnerMatrix(2,8))-groebnerMatrix(3,9)/(groebnerMatrix(3,8))); groebnerMatrix(6,10) = (groebnerMatrix(2,10)/(groebnerMatrix(2,8))-groebnerMatrix(3,10)/(groebnerMatrix(3,8))); groebnerMatrix(6,11) = (groebnerMatrix(2,11)/(groebnerMatrix(2,8))-groebnerMatrix(3,11)/(groebnerMatrix(3,8))); groebnerMatrix(6,12) = (groebnerMatrix(2,12)/(groebnerMatrix(2,8))-groebnerMatrix(3,12)/(groebnerMatrix(3,8))); groebnerMatrix(6,13) = (groebnerMatrix(2,13)/(groebnerMatrix(2,8))-groebnerMatrix(3,13)/(groebnerMatrix(3,8))); groebnerMatrix(6,14) = (groebnerMatrix(2,14)/(groebnerMatrix(2,8))-groebnerMatrix(3,14)/(groebnerMatrix(3,8))); groebnerMatrix(6,15) = (groebnerMatrix(2,15)/(groebnerMatrix(2,8))-groebnerMatrix(3,15)/(groebnerMatrix(3,8))); groebnerMatrix(6,16) = (groebnerMatrix(2,16)/(groebnerMatrix(2,8))-groebnerMatrix(3,16)/(groebnerMatrix(3,8))); groebnerMatrix(6,17) = (groebnerMatrix(2,17)/(groebnerMatrix(2,8))-groebnerMatrix(3,17)/(groebnerMatrix(3,8))); } void opengv::absolute_pose::modules::gpnp3::sPolynomial7( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(7,4) = (groebnerMatrix(4,10)/(groebnerMatrix(4,9))-groebnerMatrix(6,12)/(groebnerMatrix(6,11))); groebnerMatrix(7,5) = groebnerMatrix(4,11)/(groebnerMatrix(4,9)); groebnerMatrix(7,6) = (groebnerMatrix(4,12)/(groebnerMatrix(4,9))-groebnerMatrix(6,13)/(groebnerMatrix(6,11))); groebnerMatrix(7,7) = groebnerMatrix(4,13)/(groebnerMatrix(4,9)); groebnerMatrix(7,9) = -groebnerMatrix(6,14)/(groebnerMatrix(6,11)); groebnerMatrix(7,10) = -groebnerMatrix(6,15)/(groebnerMatrix(6,11)); groebnerMatrix(7,11) = groebnerMatrix(4,14)/(groebnerMatrix(4,9)); groebnerMatrix(7,12) = (groebnerMatrix(4,15)/(groebnerMatrix(4,9))-groebnerMatrix(6,16)/(groebnerMatrix(6,11))); groebnerMatrix(7,13) = groebnerMatrix(4,16)/(groebnerMatrix(4,9)); groebnerMatrix(7,15) = -groebnerMatrix(6,17)/(groebnerMatrix(6,11)); groebnerMatrix(7,16) = groebnerMatrix(4,17)/(groebnerMatrix(4,9)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial8( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(8,3) = (groebnerMatrix(3,9)/(groebnerMatrix(3,8))-groebnerMatrix(6,12)/(groebnerMatrix(6,11))); groebnerMatrix(8,4) = groebnerMatrix(3,10)/(groebnerMatrix(3,8)); groebnerMatrix(8,5) = (groebnerMatrix(3,11)/(groebnerMatrix(3,8))-groebnerMatrix(6,13)/(groebnerMatrix(6,11))); groebnerMatrix(8,6) = groebnerMatrix(3,12)/(groebnerMatrix(3,8)); groebnerMatrix(8,7) = groebnerMatrix(3,13)/(groebnerMatrix(3,8)); groebnerMatrix(8,8) = -groebnerMatrix(6,14)/(groebnerMatrix(6,11)); groebnerMatrix(8,9) = -groebnerMatrix(6,15)/(groebnerMatrix(6,11)); groebnerMatrix(8,11) = (groebnerMatrix(3,14)/(groebnerMatrix(3,8))-groebnerMatrix(6,16)/(groebnerMatrix(6,11))); groebnerMatrix(8,12) = groebnerMatrix(3,15)/(groebnerMatrix(3,8)); groebnerMatrix(8,13) = groebnerMatrix(3,16)/(groebnerMatrix(3,8)); groebnerMatrix(8,14) = -groebnerMatrix(6,17)/(groebnerMatrix(6,11)); groebnerMatrix(8,16) = groebnerMatrix(3,17)/(groebnerMatrix(3,8)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial9( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(9,1) = groebnerMatrix(4,10)/(groebnerMatrix(4,9)); groebnerMatrix(9,2) = -groebnerMatrix(5,11)/(groebnerMatrix(5,10)); groebnerMatrix(9,3) = (groebnerMatrix(4,11)/(groebnerMatrix(4,9))-groebnerMatrix(5,12)/(groebnerMatrix(5,10))); groebnerMatrix(9,4) = groebnerMatrix(4,12)/(groebnerMatrix(4,9)); groebnerMatrix(9,5) = -groebnerMatrix(5,13)/(groebnerMatrix(5,10)); groebnerMatrix(9,6) = groebnerMatrix(4,13)/(groebnerMatrix(4,9)); groebnerMatrix(9,8) = -groebnerMatrix(5,14)/(groebnerMatrix(5,10)); groebnerMatrix(9,9) = (groebnerMatrix(4,14)/(groebnerMatrix(4,9))-groebnerMatrix(5,15)/(groebnerMatrix(5,10))); groebnerMatrix(9,10) = groebnerMatrix(4,15)/(groebnerMatrix(4,9)); groebnerMatrix(9,11) = -groebnerMatrix(5,16)/(groebnerMatrix(5,10)); groebnerMatrix(9,12) = groebnerMatrix(4,16)/(groebnerMatrix(4,9)); groebnerMatrix(9,14) = -groebnerMatrix(5,17)/(groebnerMatrix(5,10)); groebnerMatrix(9,15) = groebnerMatrix(4,17)/(groebnerMatrix(4,9)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial10( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(10,0) = (groebnerMatrix(3,9)/(groebnerMatrix(3,8))-groebnerMatrix(4,10)/(groebnerMatrix(4,9))); groebnerMatrix(10,1) = groebnerMatrix(3,10)/(groebnerMatrix(3,8)); groebnerMatrix(10,2) = -groebnerMatrix(4,11)/(groebnerMatrix(4,9)); groebnerMatrix(10,3) = (groebnerMatrix(3,11)/(groebnerMatrix(3,8))-groebnerMatrix(4,12)/(groebnerMatrix(4,9))); groebnerMatrix(10,4) = groebnerMatrix(3,12)/(groebnerMatrix(3,8)); groebnerMatrix(10,5) = -groebnerMatrix(4,13)/(groebnerMatrix(4,9)); groebnerMatrix(10,6) = groebnerMatrix(3,13)/(groebnerMatrix(3,8)); groebnerMatrix(10,8) = -groebnerMatrix(4,14)/(groebnerMatrix(4,9)); groebnerMatrix(10,9) = (groebnerMatrix(3,14)/(groebnerMatrix(3,8))-groebnerMatrix(4,15)/(groebnerMatrix(4,9))); groebnerMatrix(10,10) = groebnerMatrix(3,15)/(groebnerMatrix(3,8)); groebnerMatrix(10,11) = -groebnerMatrix(4,16)/(groebnerMatrix(4,9)); groebnerMatrix(10,12) = groebnerMatrix(3,16)/(groebnerMatrix(3,8)); groebnerMatrix(10,14) = -groebnerMatrix(4,17)/(groebnerMatrix(4,9)); groebnerMatrix(10,15) = groebnerMatrix(3,17)/(groebnerMatrix(3,8)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial11( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(11,11) = -groebnerMatrix(10,14)/(groebnerMatrix(10,13)); groebnerMatrix(11,12) = (groebnerMatrix(8,12)/(groebnerMatrix(8,7))-groebnerMatrix(10,15)/(groebnerMatrix(10,13))); groebnerMatrix(11,13) = (groebnerMatrix(8,13)/(groebnerMatrix(8,7))-groebnerMatrix(10,16)/(groebnerMatrix(10,13))); groebnerMatrix(11,14) = groebnerMatrix(8,14)/(groebnerMatrix(8,7)); groebnerMatrix(11,15) = groebnerMatrix(8,15)/(groebnerMatrix(8,7)); groebnerMatrix(11,16) = (groebnerMatrix(8,16)/(groebnerMatrix(8,7))-groebnerMatrix(10,17)/(groebnerMatrix(10,13))); groebnerMatrix(11,17) = groebnerMatrix(8,17)/(groebnerMatrix(8,7)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial12( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(12,7) = (groebnerMatrix(7,7)/(groebnerMatrix(7,6))-groebnerMatrix(9,13)/(groebnerMatrix(9,12))); groebnerMatrix(12,11) = -groebnerMatrix(9,14)/(groebnerMatrix(9,12)); groebnerMatrix(12,12) = (groebnerMatrix(7,12)/(groebnerMatrix(7,6))-groebnerMatrix(9,15)/(groebnerMatrix(9,12))); groebnerMatrix(12,13) = (groebnerMatrix(7,13)/(groebnerMatrix(7,6))-groebnerMatrix(9,16)/(groebnerMatrix(9,12))); groebnerMatrix(12,14) = groebnerMatrix(7,14)/(groebnerMatrix(7,6)); groebnerMatrix(12,15) = groebnerMatrix(7,15)/(groebnerMatrix(7,6)); groebnerMatrix(12,16) = (groebnerMatrix(7,16)/(groebnerMatrix(7,6))-groebnerMatrix(9,17)/(groebnerMatrix(9,12))); groebnerMatrix(12,17) = groebnerMatrix(7,17)/(groebnerMatrix(7,6)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial13( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(13,7) = groebnerMatrix(9,13)/(groebnerMatrix(9,12)); groebnerMatrix(13,9) = -groebnerMatrix(10,14)/(groebnerMatrix(10,13)); groebnerMatrix(13,10) = -groebnerMatrix(10,15)/(groebnerMatrix(10,13)); groebnerMatrix(13,11) = groebnerMatrix(9,14)/(groebnerMatrix(9,12)); groebnerMatrix(13,12) = (groebnerMatrix(9,15)/(groebnerMatrix(9,12))-groebnerMatrix(10,16)/(groebnerMatrix(10,13))); groebnerMatrix(13,13) = groebnerMatrix(9,16)/(groebnerMatrix(9,12)); groebnerMatrix(13,15) = -groebnerMatrix(10,17)/(groebnerMatrix(10,13)); groebnerMatrix(13,16) = groebnerMatrix(9,17)/(groebnerMatrix(9,12)); } void opengv::absolute_pose::modules::gpnp3::sPolynomial14( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(14,14) = groebnerMatrix(10,14)/(groebnerMatrix(10,13)); groebnerMatrix(14,15) = groebnerMatrix(10,15)/(groebnerMatrix(10,13)); groebnerMatrix(14,16) = (groebnerMatrix(10,16)/(groebnerMatrix(10,13))-groebnerMatrix(13,17)/(groebnerMatrix(13,16))); groebnerMatrix(14,17) = groebnerMatrix(10,17)/(groebnerMatrix(10,13)); } opengv/src/absolute_pose/modules/gpnp3/init.cpp0000664016516101651610000002655113344612246020621 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp3::init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Matrix & k, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ) { Eigen::Vector3d temp = c0-c1; double c01w = temp.norm()*temp.norm(); temp = c0-c2; double c02w = temp.norm()*temp.norm(); temp = c0-c3; double c03w = temp.norm()*temp.norm(); temp = c1-c2; double c12w = temp.norm()*temp.norm(); groebnerMatrix(0,8) = ((((((((-2*k(0,0)*k(3,0)-2*k(1,0)*k(4,0))-2*k(2,0)*k(5,0))+pow(k(0,0),2))+pow(k(3,0),2))+pow(k(1,0),2))+pow(k(4,0),2))+pow(k(2,0),2))+pow(k(5,0),2)); groebnerMatrix(0,9) = (((((((((((2*m(0,0)*k(0,0)-2*m(0,0)*k(3,0))-2*k(0,0)*m(3,0))+2*m(3,0)*k(3,0))+2*m(1,0)*k(1,0))-2*m(1,0)*k(4,0))-2*k(1,0)*m(4,0))+2*m(4,0)*k(4,0))+2*m(2,0)*k(2,0))-2*m(2,0)*k(5,0))-2*k(2,0)*m(5,0))+2*m(5,0)*k(5,0)); groebnerMatrix(0,10) = ((((((((-2*m(0,0)*m(3,0)-2*m(1,0)*m(4,0))-2*m(2,0)*m(5,0))+pow(m(0,0),2))+pow(m(3,0),2))+pow(m(1,0),2))+pow(m(4,0),2))+pow(m(2,0),2))+pow(m(5,0),2)); groebnerMatrix(0,11) = (((((((((((2*n(0,0)*k(0,0)-2*n(0,0)*k(3,0))-2*k(0,0)*n(3,0))+2*n(3,0)*k(3,0))+2*n(1,0)*k(1,0))-2*n(1,0)*k(4,0))-2*k(1,0)*n(4,0))+2*n(4,0)*k(4,0))+2*n(2,0)*k(2,0))-2*n(2,0)*k(5,0))-2*k(2,0)*n(5,0))+2*n(5,0)*k(5,0)); groebnerMatrix(0,12) = (((((((((((2*n(0,0)*m(0,0)-2*n(0,0)*m(3,0))-2*m(0,0)*n(3,0))+2*n(3,0)*m(3,0))+2*n(1,0)*m(1,0))-2*n(1,0)*m(4,0))-2*m(1,0)*n(4,0))+2*n(4,0)*m(4,0))+2*n(2,0)*m(2,0))-2*n(2,0)*m(5,0))-2*m(2,0)*n(5,0))+2*n(5,0)*m(5,0)); groebnerMatrix(0,13) = ((((((((-2*n(0,0)*n(3,0)-2*n(1,0)*n(4,0))-2*n(2,0)*n(5,0))+pow(n(0,0),2))+pow(n(3,0),2))+pow(n(1,0),2))+pow(n(4,0),2))+pow(n(2,0),2))+pow(n(5,0),2)); groebnerMatrix(0,14) = (((((((((((2*a(0,0)*k(0,0)-2*a(0,0)*k(3,0))-2*k(0,0)*a(3,0))+2*a(3,0)*k(3,0))+2*a(1,0)*k(1,0))-2*a(1,0)*k(4,0))-2*k(1,0)*a(4,0))+2*a(4,0)*k(4,0))+2*a(2,0)*k(2,0))-2*a(2,0)*k(5,0))-2*k(2,0)*a(5,0))+2*a(5,0)*k(5,0)); groebnerMatrix(0,15) = (((((((((((2*a(0,0)*m(0,0)-2*a(0,0)*m(3,0))-2*m(0,0)*a(3,0))+2*a(3,0)*m(3,0))+2*a(1,0)*m(1,0))-2*a(1,0)*m(4,0))-2*m(1,0)*a(4,0))+2*a(4,0)*m(4,0))+2*a(2,0)*m(2,0))-2*a(2,0)*m(5,0))-2*m(2,0)*a(5,0))+2*a(5,0)*m(5,0)); groebnerMatrix(0,16) = (((((((((((2*a(0,0)*n(0,0)-2*a(0,0)*n(3,0))-2*n(0,0)*a(3,0))+2*a(3,0)*n(3,0))+2*a(1,0)*n(1,0))-2*a(1,0)*n(4,0))-2*n(1,0)*a(4,0))+2*a(4,0)*n(4,0))+2*a(2,0)*n(2,0))-2*a(2,0)*n(5,0))-2*n(2,0)*a(5,0))+2*a(5,0)*n(5,0)); groebnerMatrix(0,17) = (((((((((-c01w+pow(a(0,0),2))-2*a(0,0)*a(3,0))+pow(a(3,0),2))+pow(a(1,0),2))-2*a(1,0)*a(4,0))+pow(a(4,0),2))+pow(a(2,0),2))-2*a(2,0)*a(5,0))+pow(a(5,0),2)); groebnerMatrix(1,8) = ((((((((-2*k(0,0)*k(6,0)-2*k(1,0)*k(7,0))-2*k(2,0)*k(8,0))+pow(k(0,0),2))+pow(k(1,0),2))+pow(k(2,0),2))+pow(k(6,0),2))+pow(k(7,0),2))+pow(k(8,0),2)); groebnerMatrix(1,9) = (((((((((((2*m(0,0)*k(0,0)+2*m(1,0)*k(1,0))+2*m(2,0)*k(2,0))-2*m(0,0)*k(6,0))-2*k(0,0)*m(6,0))+2*m(6,0)*k(6,0))-2*m(1,0)*k(7,0))-2*k(1,0)*m(7,0))+2*m(7,0)*k(7,0))-2*m(2,0)*k(8,0))-2*k(2,0)*m(8,0))+2*m(8,0)*k(8,0)); groebnerMatrix(1,10) = ((((((((-2*m(0,0)*m(6,0)-2*m(1,0)*m(7,0))-2*m(2,0)*m(8,0))+pow(m(0,0),2))+pow(m(1,0),2))+pow(m(2,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2)); groebnerMatrix(1,11) = (((((((((((2*n(0,0)*k(0,0)+2*n(1,0)*k(1,0))+2*n(2,0)*k(2,0))-2*n(0,0)*k(6,0))-2*k(0,0)*n(6,0))+2*n(6,0)*k(6,0))-2*n(1,0)*k(7,0))-2*k(1,0)*n(7,0))+2*n(7,0)*k(7,0))-2*n(2,0)*k(8,0))-2*k(2,0)*n(8,0))+2*n(8,0)*k(8,0)); groebnerMatrix(1,12) = (((((((((((2*n(0,0)*m(0,0)+2*n(1,0)*m(1,0))+2*n(2,0)*m(2,0))-2*n(0,0)*m(6,0))-2*m(0,0)*n(6,0))+2*n(6,0)*m(6,0))-2*n(1,0)*m(7,0))-2*m(1,0)*n(7,0))+2*n(7,0)*m(7,0))-2*n(2,0)*m(8,0))-2*m(2,0)*n(8,0))+2*n(8,0)*m(8,0)); groebnerMatrix(1,13) = ((((((((-2*n(0,0)*n(6,0)-2*n(1,0)*n(7,0))-2*n(2,0)*n(8,0))+pow(n(0,0),2))+pow(n(1,0),2))+pow(n(2,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2)); groebnerMatrix(1,14) = (((((((((((2*a(0,0)*k(0,0)+2*a(1,0)*k(1,0))+2*a(2,0)*k(2,0))-2*a(0,0)*k(6,0))-2*k(0,0)*a(6,0))+2*a(6,0)*k(6,0))-2*a(1,0)*k(7,0))-2*k(1,0)*a(7,0))+2*a(7,0)*k(7,0))-2*a(2,0)*k(8,0))-2*k(2,0)*a(8,0))+2*a(8,0)*k(8,0)); groebnerMatrix(1,15) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))-2*a(0,0)*m(6,0))-2*m(0,0)*a(6,0))+2*a(6,0)*m(6,0))-2*a(1,0)*m(7,0))-2*m(1,0)*a(7,0))+2*a(7,0)*m(7,0))-2*a(2,0)*m(8,0))-2*m(2,0)*a(8,0))+2*a(8,0)*m(8,0)); groebnerMatrix(1,16) = (((((((((((2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))-2*a(0,0)*n(6,0))-2*n(0,0)*a(6,0))+2*a(6,0)*n(6,0))-2*a(1,0)*n(7,0))-2*n(1,0)*a(7,0))+2*a(7,0)*n(7,0))-2*a(2,0)*n(8,0))-2*n(2,0)*a(8,0))+2*a(8,0)*n(8,0)); groebnerMatrix(1,17) = (((((((((-c02w+pow(a(0,0),2))+pow(a(1,0),2))+pow(a(2,0),2))-2*a(0,0)*a(6,0))+pow(a(6,0),2))-2*a(1,0)*a(7,0))+pow(a(7,0),2))-2*a(2,0)*a(8,0))+pow(a(8,0),2)); groebnerMatrix(2,8) = ((((((((pow(k(0,0),2)+pow(k(1,0),2))+pow(k(2,0),2))+pow(k(9,0),2))+pow(k(10,0),2))+pow(k(11,0),2))-2*k(0,0)*k(9,0))-2*k(1,0)*k(10,0))-2*k(2,0)*k(11,0)); groebnerMatrix(2,9) = (((((((((((2*m(0,0)*k(0,0)+2*m(1,0)*k(1,0))+2*m(2,0)*k(2,0))-2*m(0,0)*k(9,0))-2*k(0,0)*m(9,0))+2*m(9,0)*k(9,0))-2*m(1,0)*k(10,0))-2*k(1,0)*m(10,0))+2*m(10,0)*k(10,0))-2*m(2,0)*k(11,0))-2*k(2,0)*m(11,0))+2*m(11,0)*k(11,0)); groebnerMatrix(2,10) = ((((((((pow(m(0,0),2)+pow(m(1,0),2))+pow(m(2,0),2))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2))-2*m(0,0)*m(9,0))-2*m(1,0)*m(10,0))-2*m(2,0)*m(11,0)); groebnerMatrix(2,11) = (((((((((((2*n(0,0)*k(0,0)+2*n(1,0)*k(1,0))+2*n(2,0)*k(2,0))-2*n(0,0)*k(9,0))-2*k(0,0)*n(9,0))+2*n(9,0)*k(9,0))-2*n(1,0)*k(10,0))-2*k(1,0)*n(10,0))+2*n(10,0)*k(10,0))-2*n(2,0)*k(11,0))-2*k(2,0)*n(11,0))+2*n(11,0)*k(11,0)); groebnerMatrix(2,12) = (((((((((((2*n(0,0)*m(0,0)+2*n(1,0)*m(1,0))+2*n(2,0)*m(2,0))-2*n(0,0)*m(9,0))-2*m(0,0)*n(9,0))+2*n(9,0)*m(9,0))-2*n(1,0)*m(10,0))-2*m(1,0)*n(10,0))+2*n(10,0)*m(10,0))-2*n(2,0)*m(11,0))-2*m(2,0)*n(11,0))+2*n(11,0)*m(11,0)); groebnerMatrix(2,13) = ((((((((pow(n(0,0),2)+pow(n(1,0),2))+pow(n(2,0),2))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2))-2*n(0,0)*n(9,0))-2*n(1,0)*n(10,0))-2*n(2,0)*n(11,0)); groebnerMatrix(2,14) = (((((((((((2*a(0,0)*k(0,0)+2*a(1,0)*k(1,0))+2*a(2,0)*k(2,0))-2*a(0,0)*k(9,0))-2*k(0,0)*a(9,0))+2*a(9,0)*k(9,0))-2*a(1,0)*k(10,0))-2*k(1,0)*a(10,0))+2*a(10,0)*k(10,0))-2*a(2,0)*k(11,0))-2*k(2,0)*a(11,0))+2*a(11,0)*k(11,0)); groebnerMatrix(2,15) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))-2*a(0,0)*m(9,0))-2*m(0,0)*a(9,0))+2*a(9,0)*m(9,0))-2*a(1,0)*m(10,0))-2*m(1,0)*a(10,0))+2*a(10,0)*m(10,0))-2*a(2,0)*m(11,0))-2*m(2,0)*a(11,0))+2*a(11,0)*m(11,0)); groebnerMatrix(2,16) = (((((((((((2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))-2*a(0,0)*n(9,0))-2*n(0,0)*a(9,0))+2*a(9,0)*n(9,0))-2*a(1,0)*n(10,0))-2*n(1,0)*a(10,0))+2*a(10,0)*n(10,0))-2*a(2,0)*n(11,0))-2*n(2,0)*a(11,0))+2*a(11,0)*n(11,0)); groebnerMatrix(2,17) = (((((((((-c03w+pow(a(0,0),2))+pow(a(1,0),2))+pow(a(2,0),2))-2*a(0,0)*a(9,0))+pow(a(9,0),2))-2*a(1,0)*a(10,0))+pow(a(10,0),2))-2*a(2,0)*a(11,0))+pow(a(11,0),2)); groebnerMatrix(3,8) = ((((((((pow(k(3,0),2)+pow(k(4,0),2))+pow(k(5,0),2))+pow(k(6,0),2))+pow(k(7,0),2))+pow(k(8,0),2))-2*k(3,0)*k(6,0))-2*k(4,0)*k(7,0))-2*k(5,0)*k(8,0)); groebnerMatrix(3,9) = (((((((((((2*m(3,0)*k(3,0)+2*m(4,0)*k(4,0))+2*m(5,0)*k(5,0))+2*m(6,0)*k(6,0))+2*m(7,0)*k(7,0))+2*m(8,0)*k(8,0))-2*m(3,0)*k(6,0))-2*k(3,0)*m(6,0))-2*m(4,0)*k(7,0))-2*k(4,0)*m(7,0))-2*m(5,0)*k(8,0))-2*k(5,0)*m(8,0)); groebnerMatrix(3,10) = ((((((((pow(m(3,0),2)+pow(m(4,0),2))+pow(m(5,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2))-2*m(3,0)*m(6,0))-2*m(4,0)*m(7,0))-2*m(5,0)*m(8,0)); groebnerMatrix(3,11) = (((((((((((2*n(3,0)*k(3,0)+2*n(4,0)*k(4,0))+2*n(5,0)*k(5,0))+2*n(6,0)*k(6,0))+2*n(7,0)*k(7,0))+2*n(8,0)*k(8,0))-2*n(3,0)*k(6,0))-2*k(3,0)*n(6,0))-2*n(4,0)*k(7,0))-2*k(4,0)*n(7,0))-2*n(5,0)*k(8,0))-2*k(5,0)*n(8,0)); groebnerMatrix(3,12) = (((((((((((2*n(3,0)*m(3,0)+2*n(4,0)*m(4,0))+2*n(5,0)*m(5,0))+2*n(6,0)*m(6,0))+2*n(7,0)*m(7,0))+2*n(8,0)*m(8,0))-2*n(3,0)*m(6,0))-2*m(3,0)*n(6,0))-2*n(4,0)*m(7,0))-2*m(4,0)*n(7,0))-2*n(5,0)*m(8,0))-2*m(5,0)*n(8,0)); groebnerMatrix(3,13) = ((((((((pow(n(3,0),2)+pow(n(4,0),2))+pow(n(5,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2))-2*n(3,0)*n(6,0))-2*n(4,0)*n(7,0))-2*n(5,0)*n(8,0)); groebnerMatrix(3,14) = (((((((((((2*a(3,0)*k(3,0)+2*a(4,0)*k(4,0))+2*a(5,0)*k(5,0))+2*a(6,0)*k(6,0))+2*a(7,0)*k(7,0))+2*a(8,0)*k(8,0))-2*a(3,0)*k(6,0))-2*k(3,0)*a(6,0))-2*a(4,0)*k(7,0))-2*k(4,0)*a(7,0))-2*a(5,0)*k(8,0))-2*k(5,0)*a(8,0)); groebnerMatrix(3,15) = (((((((((((2*a(3,0)*m(3,0)+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(6,0)*m(6,0))+2*a(7,0)*m(7,0))+2*a(8,0)*m(8,0))-2*a(3,0)*m(6,0))-2*m(3,0)*a(6,0))-2*a(4,0)*m(7,0))-2*m(4,0)*a(7,0))-2*a(5,0)*m(8,0))-2*m(5,0)*a(8,0)); groebnerMatrix(3,16) = (((((((((((2*a(3,0)*n(3,0)+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(6,0)*n(6,0))+2*a(7,0)*n(7,0))+2*a(8,0)*n(8,0))-2*a(3,0)*n(6,0))-2*n(3,0)*a(6,0))-2*a(4,0)*n(7,0))-2*n(4,0)*a(7,0))-2*a(5,0)*n(8,0))-2*n(5,0)*a(8,0)); groebnerMatrix(3,17) = (((((((((-c12w+pow(a(3,0),2))+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(6,0),2))+pow(a(7,0),2))+pow(a(8,0),2))-2*a(3,0)*a(6,0))-2*a(4,0)*a(7,0))-2*a(5,0)*a(8,0)); } opengv/src/absolute_pose/modules/gpnp3/code.cpp0000664016516101651610000001222313344612246020557 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp3::compute( Eigen::Matrix & groebnerMatrix ) { sPolynomial4(groebnerMatrix); sPolynomial5(groebnerMatrix); groebnerRow4_000_f(groebnerMatrix,5); sPolynomial6(groebnerMatrix); groebnerRow4_000_f(groebnerMatrix,6); groebnerRow5_000_f(groebnerMatrix,6); sPolynomial7(groebnerMatrix); groebnerRow5_100_f(groebnerMatrix,7); groebnerRow6_100_f(groebnerMatrix,7); groebnerRow4_000_f(groebnerMatrix,7); groebnerRow5_000_f(groebnerMatrix,7); groebnerRow6_000_f(groebnerMatrix,7); sPolynomial8(groebnerMatrix); groebnerRow4_100_f(groebnerMatrix,8); groebnerRow5_100_f(groebnerMatrix,8); groebnerRow6_100_f(groebnerMatrix,8); groebnerRow7_000_f(groebnerMatrix,8); groebnerRow3_000_f(groebnerMatrix,8); groebnerRow4_000_f(groebnerMatrix,8); groebnerRow5_000_f(groebnerMatrix,8); groebnerRow6_000_f(groebnerMatrix,8); sPolynomial9(groebnerMatrix); groebnerRow5_010_f(groebnerMatrix,9); groebnerRow3_100_f(groebnerMatrix,9); groebnerRow4_100_f(groebnerMatrix,9); groebnerRow5_100_f(groebnerMatrix,9); groebnerRow6_100_f(groebnerMatrix,9); groebnerRow7_000_f(groebnerMatrix,9); groebnerRow8_000_f(groebnerMatrix,9); groebnerRow3_000_f(groebnerMatrix,9); groebnerRow4_000_f(groebnerMatrix,9); groebnerRow5_000_f(groebnerMatrix,9); groebnerRow6_000_f(groebnerMatrix,9); sPolynomial10(groebnerMatrix); groebnerRow4_010_f(groebnerMatrix,10); groebnerRow5_010_f(groebnerMatrix,10); groebnerRow3_100_f(groebnerMatrix,10); groebnerRow4_100_f(groebnerMatrix,10); groebnerRow5_100_f(groebnerMatrix,10); groebnerRow6_100_f(groebnerMatrix,10); groebnerRow9_100_f(groebnerMatrix,10); groebnerRow8_000_f(groebnerMatrix,10); groebnerRow3_000_f(groebnerMatrix,10); groebnerRow4_000_f(groebnerMatrix,10); groebnerRow5_000_f(groebnerMatrix,10); groebnerRow6_000_f(groebnerMatrix,10); groebnerRow9_000_f(groebnerMatrix,10); sPolynomial11(groebnerMatrix); groebnerRow6_000_f(groebnerMatrix,11); groebnerRow9_000_f(groebnerMatrix,11); groebnerRow10_000_f(groebnerMatrix,11); sPolynomial12(groebnerMatrix); groebnerRow10_100_f(groebnerMatrix,12); groebnerRow11_100_f(groebnerMatrix,12); groebnerRow9_000_f(groebnerMatrix,12); groebnerRow10_000_f(groebnerMatrix,12); groebnerRow11_000_f(groebnerMatrix,12); sPolynomial13(groebnerMatrix); groebnerRow10_100_f(groebnerMatrix,13); groebnerRow11_010_f(groebnerMatrix,13); groebnerRow12_010_f(groebnerMatrix,13); groebnerRow11_100_f(groebnerMatrix,13); groebnerRow12_100_f(groebnerMatrix,13); groebnerRow10_000_f(groebnerMatrix,13); groebnerRow11_000_f(groebnerMatrix,13); groebnerRow12_000_f(groebnerMatrix,13); sPolynomial14(groebnerMatrix); groebnerRow11_000_f(groebnerMatrix,14); groebnerRow12_000_f(groebnerMatrix,14); groebnerRow13_000_f(groebnerMatrix,14); } opengv/src/absolute_pose/modules/gp3p/0000775016516101651610000000000013344612246016763 5ustar dimadimaopengv/src/absolute_pose/modules/gp3p/reductors.cpp0000664016516101651610000026633313344612246021516 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gp3p::groebnerRow9_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,21) / groebnerMatrix(9,21); groebnerMatrix(targetRow,21) = 0.0; groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(9,33); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(9,53); groebnerMatrix(targetRow,66) -= factor * groebnerMatrix(9,66); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(9,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(9,71); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(9,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(9,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(9,77); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(9,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(9,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(9,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(9,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(9,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow10_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,20) / groebnerMatrix(10,66); groebnerMatrix(targetRow,20) = 0.0; groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(10,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(10,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(10,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(10,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow10_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,66) / groebnerMatrix(10,66); groebnerMatrix(targetRow,66) = 0.0; groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(10,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(10,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(10,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(10,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow11_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,29) / groebnerMatrix(11,29); groebnerMatrix(targetRow,29) = 0.0; groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(11,32); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(11,43); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(11,47); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(11,52); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(11,64); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(11,68); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(11,70); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(11,71); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(11,73); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(11,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(11,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(11,77); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(11,79); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(11,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(11,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(11,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(11,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow10_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,21) / groebnerMatrix(10,66); groebnerMatrix(targetRow,21) = 0.0; groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(10,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(10,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(10,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(10,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,29) / groebnerMatrix(12,70); groebnerMatrix(targetRow,29) = 0.0; groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,30) / groebnerMatrix(12,70); groebnerMatrix(targetRow,30) = 0.0; groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,70) / groebnerMatrix(12,70); groebnerMatrix(targetRow,70) = 0.0; groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow14_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,33) / groebnerMatrix(14,33); groebnerMatrix(targetRow,33) = 0.0; groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(14,44); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(14,48); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(14,53); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(14,65); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(14,69); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(14,71); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(14,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(14,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(14,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(14,77); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(14,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(14,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(14,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(14,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(14,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_010000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,35) / groebnerMatrix(15,71); groebnerMatrix(targetRow,35) = 0.0; groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow10_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,45) / groebnerMatrix(10,66); groebnerMatrix(targetRow,45) = 0.0; groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(10,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(10,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(10,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(10,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,49) / groebnerMatrix(12,70); groebnerMatrix(targetRow,49) = 0.0; groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,50) / groebnerMatrix(15,71); groebnerMatrix(targetRow,50) = 0.0; groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,71) / groebnerMatrix(15,71); groebnerMatrix(targetRow,71) = 0.0; groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,33) / groebnerMatrix(15,71); groebnerMatrix(targetRow,33) = 0.0; groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow17_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,44) / groebnerMatrix(17,44); groebnerMatrix(targetRow,44) = 0.0; groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(17,48); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(17,53); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(17,65); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(17,69); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(17,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(17,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(17,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(17,77); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(17,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(17,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(17,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(17,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(17,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_010000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,34) / groebnerMatrix(12,70); groebnerMatrix(targetRow,34) = 0.0; groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow16_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,54) / groebnerMatrix(16,54); groebnerMatrix(targetRow,54) = 0.0; groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(16,55); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(16,56); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(16,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(16,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(16,77); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(16,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(16,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(16,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(16,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,28) / groebnerMatrix(12,70); groebnerMatrix(targetRow,28) = 0.0; groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,31) / groebnerMatrix(15,71); groebnerMatrix(targetRow,31) = 0.0; groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow19_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,11) / groebnerMatrix(19,55); groebnerMatrix(targetRow,11) = 0.0; groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(19,56); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(19,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(19,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(19,77); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(19,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(19,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(19,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(19,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow19_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,55) / groebnerMatrix(19,55); groebnerMatrix(targetRow,55) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(19,56); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(19,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(19,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(19,77); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(19,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(19,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(19,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(19,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow19_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,10) / groebnerMatrix(19,55); groebnerMatrix(targetRow,10) = 0.0; groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(19,56); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(19,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(19,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(19,77); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(19,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(19,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(19,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(19,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow18_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,43) / groebnerMatrix(18,43); groebnerMatrix(targetRow,43) = 0.0; groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(18,47); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(18,52); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(18,64); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(18,68); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(18,73); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(18,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(18,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(18,77); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(18,79); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(18,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(18,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(18,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(18,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow19_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,9) / groebnerMatrix(19,55); groebnerMatrix(targetRow,9) = 0.0; groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(19,56); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(19,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(19,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(19,77); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(19,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(19,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(19,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(19,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow20_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,42) / groebnerMatrix(20,42); groebnerMatrix(targetRow,42) = 0.0; groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(20,46); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(20,51); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(20,63); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(20,67); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(20,72); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(20,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(20,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(20,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(20,78); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(20,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(20,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(20,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(20,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_100100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,5) / groebnerMatrix(15,71); groebnerMatrix(targetRow,5) = 0.0; groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow16_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,8) / groebnerMatrix(16,54); groebnerMatrix(targetRow,8) = 0.0; groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(16,55); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(16,56); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(16,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(16,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(16,77); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(16,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(16,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(16,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(16,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow21_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,14) / groebnerMatrix(21,14); groebnerMatrix(targetRow,14) = 0.0; groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(21,48); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(21,53); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(21,56); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(21,65); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(21,69); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(21,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(21,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(21,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(21,77); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(21,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(21,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(21,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(21,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(21,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_100010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,4) / groebnerMatrix(15,71); groebnerMatrix(targetRow,4) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow16_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,7) / groebnerMatrix(16,54); groebnerMatrix(targetRow,7) = 0.0; groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(16,55); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(16,56); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(16,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(16,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(16,77); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(16,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(16,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(16,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(16,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow22_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,13) / groebnerMatrix(22,13); groebnerMatrix(targetRow,13) = 0.0; groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(22,47); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(22,52); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(22,56); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(22,64); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(22,68); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(22,73); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(22,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(22,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(22,77); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(22,79); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(22,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(22,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(22,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(22,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,32) / groebnerMatrix(15,71); groebnerMatrix(targetRow,32) = 0.0; groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow15_100001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,3) / groebnerMatrix(15,71); groebnerMatrix(targetRow,3) = 0.0; groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(15,75); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(15,76); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(15,77); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(15,81); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(15,82); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(15,83); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(15,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow16_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,6) / groebnerMatrix(16,54); groebnerMatrix(targetRow,6) = 0.0; groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(16,55); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(16,56); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(16,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(16,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(16,77); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(16,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(16,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(16,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(16,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow23_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,12) / groebnerMatrix(23,12); groebnerMatrix(targetRow,12) = 0.0; groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(23,46); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(23,51); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(23,56); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(23,63); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(23,67); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(23,72); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(23,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(23,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(23,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(23,78); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(23,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(23,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(23,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(23,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_100100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,2) / groebnerMatrix(12,70); groebnerMatrix(targetRow,2) = 0.0; groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow24_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,48) / groebnerMatrix(24,48); groebnerMatrix(targetRow,48) = 0.0; groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(24,53); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(24,56); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(24,65); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(24,69); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(24,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(24,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(24,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(24,77); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(24,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(24,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(24,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(24,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(24,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_100010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(12,70); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,4) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow25_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,47) / groebnerMatrix(25,47); groebnerMatrix(targetRow,47) = 0.0; groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(25,52); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(25,56); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(25,64); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(25,68); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(25,73); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(25,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(25,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(25,77); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(25,79); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(25,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(25,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(25,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(25,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow12_100001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,0) / groebnerMatrix(12,70); groebnerMatrix(targetRow,0) = 0.0; groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(12,71); groebnerMatrix(targetRow,6) -= factor * groebnerMatrix(12,75); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(12,76); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(12,77); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(12,81); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(12,82); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(12,83); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(12,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow10_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,19) / groebnerMatrix(10,66); groebnerMatrix(targetRow,19) = 0.0; groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(10,70); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(10,71); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(10,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(10,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(10,77); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(10,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(10,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(10,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(10,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow26_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,46) / groebnerMatrix(26,46); groebnerMatrix(targetRow,46) = 0.0; groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(26,51); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(26,56); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(26,63); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(26,67); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(26,72); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(26,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(26,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(26,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(26,78); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(26,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(26,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(26,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(26,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow28_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,52) / groebnerMatrix(28,52); groebnerMatrix(targetRow,52) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(28,56); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(28,64); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(28,68); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(28,73); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(28,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(28,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(28,77); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(28,79); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(28,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(28,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(28,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(28,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow27_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,53) / groebnerMatrix(27,53); groebnerMatrix(targetRow,53) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(27,56); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(27,65); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(27,69); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(27,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(27,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(27,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(27,77); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(27,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(27,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(27,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(27,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(27,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow29_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,51) / groebnerMatrix(29,51); groebnerMatrix(targetRow,51) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(29,56); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(29,63); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(29,67); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(29,72); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(29,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(29,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(29,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(29,78); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(29,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(29,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(29,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(29,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow31_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,42) / groebnerMatrix(31,63); groebnerMatrix(targetRow,42) = 0.0; groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(31,65); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(31,67); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(31,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(31,72); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(31,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(31,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(31,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(31,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(31,78); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(31,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(31,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(31,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(31,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(31,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow30_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,43) / groebnerMatrix(30,64); groebnerMatrix(targetRow,43) = 0.0; groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(30,65); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(30,68); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(30,69); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(30,73); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(30,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(30,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(30,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(30,77); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(30,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(30,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(30,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(30,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(30,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(30,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow31_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,63) / groebnerMatrix(31,63); groebnerMatrix(targetRow,63) = 0.0; groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(31,65); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(31,67); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(31,69); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(31,72); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(31,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(31,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(31,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(31,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(31,78); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(31,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(31,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(31,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(31,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(31,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow30_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,64) / groebnerMatrix(30,64); groebnerMatrix(targetRow,64) = 0.0; groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(30,65); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(30,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(30,69); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(30,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(30,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(30,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(30,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(30,77); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(30,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(30,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(30,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(30,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(30,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(30,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow32_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,65) / groebnerMatrix(32,65); groebnerMatrix(targetRow,65) = 0.0; groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(32,67); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(32,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(32,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(32,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(32,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(32,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(32,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(32,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow32_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,44) / groebnerMatrix(32,65); groebnerMatrix(targetRow,44) = 0.0; groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(32,67); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(32,68); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(32,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(32,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(32,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(32,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(32,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(32,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow33_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,46) / groebnerMatrix(33,67); groebnerMatrix(targetRow,46) = 0.0; groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(33,68); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(33,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(33,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(33,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(33,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(33,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(33,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(33,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow33_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,67) / groebnerMatrix(33,67); groebnerMatrix(targetRow,67) = 0.0; groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(33,68); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(33,69); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(33,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(33,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(33,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(33,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(33,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(33,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow34_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,47) / groebnerMatrix(34,68); groebnerMatrix(targetRow,47) = 0.0; groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(34,69); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(34,72); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(34,73); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(34,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(34,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(34,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(34,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(34,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(34,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(34,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(34,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(34,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(34,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(34,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow34_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,68) / groebnerMatrix(34,68); groebnerMatrix(targetRow,68) = 0.0; groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(34,69); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(34,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(34,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(34,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(34,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(34,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(34,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(34,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(34,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(34,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(34,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(34,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(34,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(34,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow35_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,48) / groebnerMatrix(35,69); groebnerMatrix(targetRow,48) = 0.0; groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(35,72); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(35,73); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(35,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(35,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(35,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(35,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(35,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(35,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(35,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(35,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(35,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(35,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(35,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow35_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,69) / groebnerMatrix(35,69); groebnerMatrix(targetRow,69) = 0.0; groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(35,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(35,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(35,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(35,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(35,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(35,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(35,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(35,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(35,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(35,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(35,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(35,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(35,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow37_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,51) / groebnerMatrix(37,72); groebnerMatrix(targetRow,51) = 0.0; groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(37,73); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(37,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(37,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(37,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(37,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(37,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(37,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow36_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,56) / groebnerMatrix(36,56); groebnerMatrix(targetRow,56) = 0.0; groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(36,72); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(36,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(36,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(36,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(36,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(36,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(36,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow37_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,72) / groebnerMatrix(37,72); groebnerMatrix(targetRow,72) = 0.0; groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(37,73); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(37,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(37,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(37,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(37,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(37,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(37,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow38_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,52) / groebnerMatrix(38,73); groebnerMatrix(targetRow,52) = 0.0; groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(38,74); groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(38,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(38,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(38,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(38,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(38,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(38,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow38_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,73) / groebnerMatrix(38,73); groebnerMatrix(targetRow,73) = 0.0; groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(38,74); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(38,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(38,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(38,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(38,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(38,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(38,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow39_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,53) / groebnerMatrix(39,74); groebnerMatrix(targetRow,53) = 0.0; groebnerMatrix(targetRow,54) -= factor * groebnerMatrix(39,75); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(39,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(39,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(39,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(39,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(39,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(39,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow39_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,74) / groebnerMatrix(39,74); groebnerMatrix(targetRow,74) = 0.0; groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(39,75); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(39,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(39,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(39,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(39,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(39,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(39,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow40_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,54) / groebnerMatrix(40,75); groebnerMatrix(targetRow,54) = 0.0; groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(40,76); groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(40,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(40,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(40,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(40,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(40,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(40,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow40_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,75) / groebnerMatrix(40,75); groebnerMatrix(targetRow,75) = 0.0; groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(40,76); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(40,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(40,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(40,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(40,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(40,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(40,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(40,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(40,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow32_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,18) / groebnerMatrix(32,65); groebnerMatrix(targetRow,18) = 0.0; groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(32,67); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(32,68); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(32,69); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(32,72); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(32,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(32,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(32,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(32,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(32,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(32,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(32,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(32,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(32,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(32,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(32,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(32,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow33_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,23) / groebnerMatrix(33,67); groebnerMatrix(targetRow,23) = 0.0; groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(33,68); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(33,69); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(33,79); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(33,80); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(33,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(33,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(33,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(33,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow34_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,24) / groebnerMatrix(34,68); groebnerMatrix(targetRow,24) = 0.0; groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(34,69); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(34,72); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(34,73); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(34,74); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(34,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(34,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(34,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(34,78); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(34,79); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(34,80); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(34,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(34,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(34,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(34,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow33_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,25) / groebnerMatrix(33,67); groebnerMatrix(targetRow,25) = 0.0; groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(33,68); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(33,69); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(33,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(33,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(33,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(33,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(33,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(33,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow34_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,26) / groebnerMatrix(34,68); groebnerMatrix(targetRow,26) = 0.0; groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(34,69); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(34,72); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(34,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(34,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(34,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(34,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(34,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(34,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(34,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(34,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(34,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(34,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(34,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(34,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow35_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,27) / groebnerMatrix(35,69); groebnerMatrix(targetRow,27) = 0.0; groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(35,72); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(35,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(35,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(35,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(35,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(35,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(35,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(35,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(35,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(35,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(35,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(35,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(35,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow37_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,37) / groebnerMatrix(37,72); groebnerMatrix(targetRow,37) = 0.0; groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(37,73); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(37,79); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(37,80); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(37,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(37,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(37,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(37,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow38_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,38) / groebnerMatrix(38,73); groebnerMatrix(targetRow,38) = 0.0; groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(38,74); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(38,79); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(38,80); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(38,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(38,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(38,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(38,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow37_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,39) / groebnerMatrix(37,72); groebnerMatrix(targetRow,39) = 0.0; groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(37,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(37,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(37,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(37,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(37,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(37,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(37,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow38_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,40) / groebnerMatrix(38,73); groebnerMatrix(targetRow,40) = 0.0; groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(38,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(38,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(38,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(38,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(38,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(38,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(38,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(38,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(38,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(38,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(38,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow39_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,41) / groebnerMatrix(39,74); groebnerMatrix(targetRow,41) = 0.0; groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(39,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(39,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(39,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(39,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(39,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(39,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(39,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(39,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(39,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(39,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow41_100000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,55) / groebnerMatrix(41,76); groebnerMatrix(targetRow,55) = 0.0; groebnerMatrix(targetRow,56) -= factor * groebnerMatrix(41,77); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(41,79); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(41,80); groebnerMatrix(targetRow,75) -= factor * groebnerMatrix(41,81); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(41,82); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(41,83); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(41,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow41_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,76) / groebnerMatrix(41,76); groebnerMatrix(targetRow,76) = 0.0; groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(41,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(41,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(41,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(41,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(41,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(41,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(41,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(41,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow33_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,22) / groebnerMatrix(33,67); groebnerMatrix(targetRow,22) = 0.0; groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(33,68); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(33,69); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(33,72); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(33,73); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(33,74); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(33,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(33,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(33,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(33,78); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(33,79); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(33,80); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(33,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(33,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(33,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(33,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow37_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,36) / groebnerMatrix(37,72); groebnerMatrix(targetRow,36) = 0.0; groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(37,73); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(37,74); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(37,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(37,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(37,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(37,78); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(37,79); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(37,80); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(37,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(37,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(37,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(37,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow42_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,58) / groebnerMatrix(42,58); groebnerMatrix(targetRow,58) = 0.0; groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(42,59); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(42,60); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(42,61); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(42,62); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(42,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(42,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(42,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(42,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(42,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(42,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(42,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(42,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow31_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,16) / groebnerMatrix(31,63); groebnerMatrix(targetRow,16) = 0.0; groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(31,65); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(31,67); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(31,69); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(31,72); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(31,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(31,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(31,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(31,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(31,78); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(31,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(31,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(31,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(31,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(31,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow30_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,17) / groebnerMatrix(30,64); groebnerMatrix(targetRow,17) = 0.0; groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(30,65); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(30,68); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(30,69); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(30,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(30,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(30,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(30,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(30,77); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(30,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(30,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(30,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(30,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(30,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(30,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow36_000100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,14) / groebnerMatrix(36,56); groebnerMatrix(targetRow,14) = 0.0; groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(36,72); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,41) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,44) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,53) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(36,79); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(36,80); groebnerMatrix(targetRow,65) -= factor * groebnerMatrix(36,81); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(36,82); groebnerMatrix(targetRow,74) -= factor * groebnerMatrix(36,83); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(36,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow36_010000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,15) / groebnerMatrix(36,56); groebnerMatrix(targetRow,15) = 0.0; groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(36,72); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,48) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,49) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,50) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,55) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(36,79); groebnerMatrix(targetRow,69) -= factor * groebnerMatrix(36,80); groebnerMatrix(targetRow,70) -= factor * groebnerMatrix(36,81); groebnerMatrix(targetRow,71) -= factor * groebnerMatrix(36,82); groebnerMatrix(targetRow,76) -= factor * groebnerMatrix(36,83); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(36,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow44_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,60) / groebnerMatrix(44,60); groebnerMatrix(targetRow,60) = 0.0; groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(44,61); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(44,62); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(44,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(44,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(44,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(44,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(44,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(44,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(44,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(44,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow36_000010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,13) / groebnerMatrix(36,56); groebnerMatrix(targetRow,13) = 0.0; groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(36,72); groebnerMatrix(targetRow,38) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,40) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,43) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,47) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,52) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(36,79); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(36,80); groebnerMatrix(targetRow,64) -= factor * groebnerMatrix(36,81); groebnerMatrix(targetRow,68) -= factor * groebnerMatrix(36,82); groebnerMatrix(targetRow,73) -= factor * groebnerMatrix(36,83); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(36,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow45_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,61) / groebnerMatrix(45,61); groebnerMatrix(targetRow,61) = 0.0; groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(45,62); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(45,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(45,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(45,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(45,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(45,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(45,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(45,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(45,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow36_000001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,12) / groebnerMatrix(36,56); groebnerMatrix(targetRow,12) = 0.0; groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(36,72); groebnerMatrix(targetRow,37) -= factor * groebnerMatrix(36,73); groebnerMatrix(targetRow,39) -= factor * groebnerMatrix(36,74); groebnerMatrix(targetRow,42) -= factor * groebnerMatrix(36,75); groebnerMatrix(targetRow,46) -= factor * groebnerMatrix(36,76); groebnerMatrix(targetRow,51) -= factor * groebnerMatrix(36,77); groebnerMatrix(targetRow,57) -= factor * groebnerMatrix(36,78); groebnerMatrix(targetRow,58) -= factor * groebnerMatrix(36,79); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(36,80); groebnerMatrix(targetRow,63) -= factor * groebnerMatrix(36,81); groebnerMatrix(targetRow,67) -= factor * groebnerMatrix(36,82); groebnerMatrix(targetRow,72) -= factor * groebnerMatrix(36,83); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(36,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow43_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,57) / groebnerMatrix(43,57); groebnerMatrix(targetRow,57) = 0.0; groebnerMatrix(targetRow,59) -= factor * groebnerMatrix(43,59); groebnerMatrix(targetRow,60) -= factor * groebnerMatrix(43,60); groebnerMatrix(targetRow,61) -= factor * groebnerMatrix(43,61); groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(43,62); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(43,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(43,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(43,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(43,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(43,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(43,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(43,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(43,84); } void opengv::absolute_pose::modules::gp3p::groebnerRow46_000000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,59) / groebnerMatrix(46,59); groebnerMatrix(targetRow,59) = 0.0; groebnerMatrix(targetRow,62) -= factor * groebnerMatrix(46,62); groebnerMatrix(targetRow,77) -= factor * groebnerMatrix(46,77); groebnerMatrix(targetRow,78) -= factor * groebnerMatrix(46,78); groebnerMatrix(targetRow,79) -= factor * groebnerMatrix(46,79); groebnerMatrix(targetRow,80) -= factor * groebnerMatrix(46,80); groebnerMatrix(targetRow,81) -= factor * groebnerMatrix(46,81); groebnerMatrix(targetRow,82) -= factor * groebnerMatrix(46,82); groebnerMatrix(targetRow,83) -= factor * groebnerMatrix(46,83); groebnerMatrix(targetRow,84) -= factor * groebnerMatrix(46,84); } opengv/src/absolute_pose/modules/gp3p/spolynomials.cpp0000664016516101651610000020124713344612246022226 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gp3p::sPolynomial9( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(9,21) = (groebnerMatrix(0,21)/(groebnerMatrix(0,20))-groebnerMatrix(1,21)/(groebnerMatrix(1,20))); groebnerMatrix(9,33) = (groebnerMatrix(0,33)/(groebnerMatrix(0,20))-groebnerMatrix(1,33)/(groebnerMatrix(1,20))); groebnerMatrix(9,53) = (groebnerMatrix(0,53)/(groebnerMatrix(0,20))-groebnerMatrix(1,53)/(groebnerMatrix(1,20))); groebnerMatrix(9,66) = (groebnerMatrix(0,66)/(groebnerMatrix(0,20))-groebnerMatrix(1,66)/(groebnerMatrix(1,20))); groebnerMatrix(9,70) = -groebnerMatrix(1,70)/(groebnerMatrix(1,20)); groebnerMatrix(9,71) = (groebnerMatrix(0,71)/(groebnerMatrix(0,20))-groebnerMatrix(1,71)/(groebnerMatrix(1,20))); groebnerMatrix(9,75) = groebnerMatrix(0,75)/(groebnerMatrix(0,20)); groebnerMatrix(9,76) = (groebnerMatrix(0,76)/(groebnerMatrix(0,20))-groebnerMatrix(1,76)/(groebnerMatrix(1,20))); groebnerMatrix(9,77) = (groebnerMatrix(0,77)/(groebnerMatrix(0,20))-groebnerMatrix(1,77)/(groebnerMatrix(1,20))); groebnerMatrix(9,80) = (groebnerMatrix(0,80)/(groebnerMatrix(0,20))-groebnerMatrix(1,80)/(groebnerMatrix(1,20))); groebnerMatrix(9,81) = (groebnerMatrix(0,81)/(groebnerMatrix(0,20))-groebnerMatrix(1,81)/(groebnerMatrix(1,20))); groebnerMatrix(9,82) = groebnerMatrix(0,82)/(groebnerMatrix(0,20)); groebnerMatrix(9,83) = -groebnerMatrix(1,83)/(groebnerMatrix(1,20)); groebnerMatrix(9,84) = (groebnerMatrix(0,84)/(groebnerMatrix(0,20))-groebnerMatrix(1,84)/(groebnerMatrix(1,20))); } void opengv::absolute_pose::modules::gp3p::sPolynomial10( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(10,21) = (groebnerMatrix(1,21)/(groebnerMatrix(1,20))-groebnerMatrix(2,21)/(groebnerMatrix(2,20))); groebnerMatrix(10,33) = (groebnerMatrix(1,33)/(groebnerMatrix(1,20))-groebnerMatrix(2,33)/(groebnerMatrix(2,20))); groebnerMatrix(10,53) = (groebnerMatrix(1,53)/(groebnerMatrix(1,20))-groebnerMatrix(2,53)/(groebnerMatrix(2,20))); groebnerMatrix(10,66) = (groebnerMatrix(1,66)/(groebnerMatrix(1,20))-groebnerMatrix(2,66)/(groebnerMatrix(2,20))); groebnerMatrix(10,70) = (groebnerMatrix(1,70)/(groebnerMatrix(1,20))-groebnerMatrix(2,70)/(groebnerMatrix(2,20))); groebnerMatrix(10,71) = (groebnerMatrix(1,71)/(groebnerMatrix(1,20))-groebnerMatrix(2,71)/(groebnerMatrix(2,20))); groebnerMatrix(10,75) = -groebnerMatrix(2,75)/(groebnerMatrix(2,20)); groebnerMatrix(10,76) = groebnerMatrix(1,76)/(groebnerMatrix(1,20)); groebnerMatrix(10,77) = (groebnerMatrix(1,77)/(groebnerMatrix(1,20))-groebnerMatrix(2,77)/(groebnerMatrix(2,20))); groebnerMatrix(10,80) = (groebnerMatrix(1,80)/(groebnerMatrix(1,20))-groebnerMatrix(2,80)/(groebnerMatrix(2,20))); groebnerMatrix(10,81) = groebnerMatrix(1,81)/(groebnerMatrix(1,20)); groebnerMatrix(10,82) = -groebnerMatrix(2,82)/(groebnerMatrix(2,20)); groebnerMatrix(10,83) = (groebnerMatrix(1,83)/(groebnerMatrix(1,20))-groebnerMatrix(2,83)/(groebnerMatrix(2,20))); groebnerMatrix(10,84) = (groebnerMatrix(1,84)/(groebnerMatrix(1,20))-groebnerMatrix(2,84)/(groebnerMatrix(2,20))); } void opengv::absolute_pose::modules::gp3p::sPolynomial11( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(11,20) = (groebnerMatrix(3,20)/(groebnerMatrix(3,19))-groebnerMatrix(4,20)/(groebnerMatrix(4,19))); groebnerMatrix(11,32) = (groebnerMatrix(3,32)/(groebnerMatrix(3,19))-groebnerMatrix(4,32)/(groebnerMatrix(4,19))); groebnerMatrix(11,52) = (groebnerMatrix(3,52)/(groebnerMatrix(3,19))-groebnerMatrix(4,52)/(groebnerMatrix(4,19))); groebnerMatrix(11,66) = (groebnerMatrix(3,66)/(groebnerMatrix(3,19))-groebnerMatrix(4,66)/(groebnerMatrix(4,19))); groebnerMatrix(11,70) = -groebnerMatrix(4,70)/(groebnerMatrix(4,19)); groebnerMatrix(11,71) = (groebnerMatrix(3,71)/(groebnerMatrix(3,19))-groebnerMatrix(4,71)/(groebnerMatrix(4,19))); groebnerMatrix(11,75) = groebnerMatrix(3,75)/(groebnerMatrix(3,19)); groebnerMatrix(11,76) = (groebnerMatrix(3,76)/(groebnerMatrix(3,19))-groebnerMatrix(4,76)/(groebnerMatrix(4,19))); groebnerMatrix(11,77) = (groebnerMatrix(3,77)/(groebnerMatrix(3,19))-groebnerMatrix(4,77)/(groebnerMatrix(4,19))); groebnerMatrix(11,79) = (groebnerMatrix(3,79)/(groebnerMatrix(3,19))-groebnerMatrix(4,79)/(groebnerMatrix(4,19))); groebnerMatrix(11,81) = (groebnerMatrix(3,81)/(groebnerMatrix(3,19))-groebnerMatrix(4,81)/(groebnerMatrix(4,19))); groebnerMatrix(11,82) = groebnerMatrix(3,82)/(groebnerMatrix(3,19)); groebnerMatrix(11,83) = -groebnerMatrix(4,83)/(groebnerMatrix(4,19)); groebnerMatrix(11,84) = (groebnerMatrix(3,84)/(groebnerMatrix(3,19))-groebnerMatrix(4,84)/(groebnerMatrix(4,19))); } void opengv::absolute_pose::modules::gp3p::sPolynomial12( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(12,20) = (groebnerMatrix(4,20)/(groebnerMatrix(4,19))-groebnerMatrix(5,20)/(groebnerMatrix(5,19))); groebnerMatrix(12,32) = (groebnerMatrix(4,32)/(groebnerMatrix(4,19))-groebnerMatrix(5,32)/(groebnerMatrix(5,19))); groebnerMatrix(12,52) = (groebnerMatrix(4,52)/(groebnerMatrix(4,19))-groebnerMatrix(5,52)/(groebnerMatrix(5,19))); groebnerMatrix(12,66) = (groebnerMatrix(4,66)/(groebnerMatrix(4,19))-groebnerMatrix(5,66)/(groebnerMatrix(5,19))); groebnerMatrix(12,70) = (groebnerMatrix(4,70)/(groebnerMatrix(4,19))-groebnerMatrix(5,70)/(groebnerMatrix(5,19))); groebnerMatrix(12,71) = (groebnerMatrix(4,71)/(groebnerMatrix(4,19))-groebnerMatrix(5,71)/(groebnerMatrix(5,19))); groebnerMatrix(12,75) = -groebnerMatrix(5,75)/(groebnerMatrix(5,19)); groebnerMatrix(12,76) = groebnerMatrix(4,76)/(groebnerMatrix(4,19)); groebnerMatrix(12,77) = (groebnerMatrix(4,77)/(groebnerMatrix(4,19))-groebnerMatrix(5,77)/(groebnerMatrix(5,19))); groebnerMatrix(12,79) = (groebnerMatrix(4,79)/(groebnerMatrix(4,19))-groebnerMatrix(5,79)/(groebnerMatrix(5,19))); groebnerMatrix(12,81) = groebnerMatrix(4,81)/(groebnerMatrix(4,19)); groebnerMatrix(12,82) = -groebnerMatrix(5,82)/(groebnerMatrix(5,19)); groebnerMatrix(12,83) = (groebnerMatrix(4,83)/(groebnerMatrix(4,19))-groebnerMatrix(5,83)/(groebnerMatrix(5,19))); groebnerMatrix(12,84) = (groebnerMatrix(4,84)/(groebnerMatrix(4,19))-groebnerMatrix(5,84)/(groebnerMatrix(5,19))); } void opengv::absolute_pose::modules::gp3p::sPolynomial13( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(13,20) = groebnerMatrix(5,20)/(groebnerMatrix(5,19)); groebnerMatrix(13,21) = -groebnerMatrix(6,21)/(groebnerMatrix(6,19)); groebnerMatrix(13,32) = groebnerMatrix(5,32)/(groebnerMatrix(5,19)); groebnerMatrix(13,33) = -groebnerMatrix(6,33)/(groebnerMatrix(6,19)); groebnerMatrix(13,52) = groebnerMatrix(5,52)/(groebnerMatrix(5,19)); groebnerMatrix(13,53) = -groebnerMatrix(6,53)/(groebnerMatrix(6,19)); groebnerMatrix(13,66) = (groebnerMatrix(5,66)/(groebnerMatrix(5,19))-groebnerMatrix(6,66)/(groebnerMatrix(6,19))); groebnerMatrix(13,70) = groebnerMatrix(5,70)/(groebnerMatrix(5,19)); groebnerMatrix(13,71) = (groebnerMatrix(5,71)/(groebnerMatrix(5,19))-groebnerMatrix(6,71)/(groebnerMatrix(6,19))); groebnerMatrix(13,75) = (groebnerMatrix(5,75)/(groebnerMatrix(5,19))-groebnerMatrix(6,75)/(groebnerMatrix(6,19))); groebnerMatrix(13,76) = -groebnerMatrix(6,76)/(groebnerMatrix(6,19)); groebnerMatrix(13,77) = (groebnerMatrix(5,77)/(groebnerMatrix(5,19))-groebnerMatrix(6,77)/(groebnerMatrix(6,19))); groebnerMatrix(13,79) = groebnerMatrix(5,79)/(groebnerMatrix(5,19)); groebnerMatrix(13,80) = -groebnerMatrix(6,80)/(groebnerMatrix(6,19)); groebnerMatrix(13,81) = -groebnerMatrix(6,81)/(groebnerMatrix(6,19)); groebnerMatrix(13,82) = (groebnerMatrix(5,82)/(groebnerMatrix(5,19))-groebnerMatrix(6,82)/(groebnerMatrix(6,19))); groebnerMatrix(13,83) = groebnerMatrix(5,83)/(groebnerMatrix(5,19)); groebnerMatrix(13,84) = (groebnerMatrix(5,84)/(groebnerMatrix(5,19))-groebnerMatrix(6,84)/(groebnerMatrix(6,19))); } void opengv::absolute_pose::modules::gp3p::sPolynomial14( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(14,21) = (groebnerMatrix(6,21)/(groebnerMatrix(6,19))-groebnerMatrix(7,21)/(groebnerMatrix(7,19))); groebnerMatrix(14,33) = (groebnerMatrix(6,33)/(groebnerMatrix(6,19))-groebnerMatrix(7,33)/(groebnerMatrix(7,19))); groebnerMatrix(14,53) = (groebnerMatrix(6,53)/(groebnerMatrix(6,19))-groebnerMatrix(7,53)/(groebnerMatrix(7,19))); groebnerMatrix(14,66) = (groebnerMatrix(6,66)/(groebnerMatrix(6,19))-groebnerMatrix(7,66)/(groebnerMatrix(7,19))); groebnerMatrix(14,70) = -groebnerMatrix(7,70)/(groebnerMatrix(7,19)); groebnerMatrix(14,71) = (groebnerMatrix(6,71)/(groebnerMatrix(6,19))-groebnerMatrix(7,71)/(groebnerMatrix(7,19))); groebnerMatrix(14,75) = groebnerMatrix(6,75)/(groebnerMatrix(6,19)); groebnerMatrix(14,76) = (groebnerMatrix(6,76)/(groebnerMatrix(6,19))-groebnerMatrix(7,76)/(groebnerMatrix(7,19))); groebnerMatrix(14,77) = (groebnerMatrix(6,77)/(groebnerMatrix(6,19))-groebnerMatrix(7,77)/(groebnerMatrix(7,19))); groebnerMatrix(14,80) = (groebnerMatrix(6,80)/(groebnerMatrix(6,19))-groebnerMatrix(7,80)/(groebnerMatrix(7,19))); groebnerMatrix(14,81) = (groebnerMatrix(6,81)/(groebnerMatrix(6,19))-groebnerMatrix(7,81)/(groebnerMatrix(7,19))); groebnerMatrix(14,82) = groebnerMatrix(6,82)/(groebnerMatrix(6,19)); groebnerMatrix(14,83) = -groebnerMatrix(7,83)/(groebnerMatrix(7,19)); groebnerMatrix(14,84) = (groebnerMatrix(6,84)/(groebnerMatrix(6,19))-groebnerMatrix(7,84)/(groebnerMatrix(7,19))); } void opengv::absolute_pose::modules::gp3p::sPolynomial15( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(15,21) = (groebnerMatrix(7,21)/(groebnerMatrix(7,19))-groebnerMatrix(8,21)/(groebnerMatrix(8,19))); groebnerMatrix(15,33) = (groebnerMatrix(7,33)/(groebnerMatrix(7,19))-groebnerMatrix(8,33)/(groebnerMatrix(8,19))); groebnerMatrix(15,53) = (groebnerMatrix(7,53)/(groebnerMatrix(7,19))-groebnerMatrix(8,53)/(groebnerMatrix(8,19))); groebnerMatrix(15,66) = (groebnerMatrix(7,66)/(groebnerMatrix(7,19))-groebnerMatrix(8,66)/(groebnerMatrix(8,19))); groebnerMatrix(15,70) = (groebnerMatrix(7,70)/(groebnerMatrix(7,19))-groebnerMatrix(8,70)/(groebnerMatrix(8,19))); groebnerMatrix(15,71) = (groebnerMatrix(7,71)/(groebnerMatrix(7,19))-groebnerMatrix(8,71)/(groebnerMatrix(8,19))); groebnerMatrix(15,75) = -groebnerMatrix(8,75)/(groebnerMatrix(8,19)); groebnerMatrix(15,76) = groebnerMatrix(7,76)/(groebnerMatrix(7,19)); groebnerMatrix(15,77) = (groebnerMatrix(7,77)/(groebnerMatrix(7,19))-groebnerMatrix(8,77)/(groebnerMatrix(8,19))); groebnerMatrix(15,80) = (groebnerMatrix(7,80)/(groebnerMatrix(7,19))-groebnerMatrix(8,80)/(groebnerMatrix(8,19))); groebnerMatrix(15,81) = groebnerMatrix(7,81)/(groebnerMatrix(7,19)); groebnerMatrix(15,82) = -groebnerMatrix(8,82)/(groebnerMatrix(8,19)); groebnerMatrix(15,83) = (groebnerMatrix(7,83)/(groebnerMatrix(7,19))-groebnerMatrix(8,83)/(groebnerMatrix(8,19))); groebnerMatrix(15,84) = (groebnerMatrix(7,84)/(groebnerMatrix(7,19))-groebnerMatrix(8,84)/(groebnerMatrix(8,19))); } void opengv::absolute_pose::modules::gp3p::sPolynomial16( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(16,35) = groebnerMatrix(12,71)/(groebnerMatrix(12,70)); groebnerMatrix(16,45) = -groebnerMatrix(15,75)/(groebnerMatrix(15,71)); groebnerMatrix(16,49) = (groebnerMatrix(12,75)/(groebnerMatrix(12,70))-groebnerMatrix(15,76)/(groebnerMatrix(15,71))); groebnerMatrix(16,50) = groebnerMatrix(12,76)/(groebnerMatrix(12,70)); groebnerMatrix(16,54) = -groebnerMatrix(15,77)/(groebnerMatrix(15,71)); groebnerMatrix(16,55) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(16,66) = -groebnerMatrix(15,81)/(groebnerMatrix(15,71)); groebnerMatrix(16,70) = (groebnerMatrix(12,81)/(groebnerMatrix(12,70))-groebnerMatrix(15,82)/(groebnerMatrix(15,71))); groebnerMatrix(16,71) = groebnerMatrix(12,82)/(groebnerMatrix(12,70)); groebnerMatrix(16,75) = -groebnerMatrix(15,83)/(groebnerMatrix(15,71)); groebnerMatrix(16,76) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(16,81) = -groebnerMatrix(15,84)/(groebnerMatrix(15,71)); groebnerMatrix(16,82) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); } void opengv::absolute_pose::modules::gp3p::sPolynomial17( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(17,44) = (groebnerMatrix(14,44)/(groebnerMatrix(14,33))-groebnerMatrix(15,75)/(groebnerMatrix(15,71))); groebnerMatrix(17,48) = (groebnerMatrix(14,48)/(groebnerMatrix(14,33))-groebnerMatrix(15,76)/(groebnerMatrix(15,71))); groebnerMatrix(17,53) = (groebnerMatrix(14,53)/(groebnerMatrix(14,33))-groebnerMatrix(15,77)/(groebnerMatrix(15,71))); groebnerMatrix(17,65) = (groebnerMatrix(14,65)/(groebnerMatrix(14,33))-groebnerMatrix(15,81)/(groebnerMatrix(15,71))); groebnerMatrix(17,69) = (groebnerMatrix(14,69)/(groebnerMatrix(14,33))-groebnerMatrix(15,82)/(groebnerMatrix(15,71))); groebnerMatrix(17,71) = groebnerMatrix(14,71)/(groebnerMatrix(14,33)); groebnerMatrix(17,74) = (groebnerMatrix(14,74)/(groebnerMatrix(14,33))-groebnerMatrix(15,83)/(groebnerMatrix(15,71))); groebnerMatrix(17,75) = groebnerMatrix(14,75)/(groebnerMatrix(14,33)); groebnerMatrix(17,76) = groebnerMatrix(14,76)/(groebnerMatrix(14,33)); groebnerMatrix(17,77) = groebnerMatrix(14,77)/(groebnerMatrix(14,33)); groebnerMatrix(17,80) = (groebnerMatrix(14,80)/(groebnerMatrix(14,33))-groebnerMatrix(15,84)/(groebnerMatrix(15,71))); groebnerMatrix(17,81) = groebnerMatrix(14,81)/(groebnerMatrix(14,33)); groebnerMatrix(17,82) = groebnerMatrix(14,82)/(groebnerMatrix(14,33)); groebnerMatrix(17,83) = groebnerMatrix(14,83)/(groebnerMatrix(14,33)); groebnerMatrix(17,84) = groebnerMatrix(14,84)/(groebnerMatrix(14,33)); } void opengv::absolute_pose::modules::gp3p::sPolynomial18( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(18,33) = groebnerMatrix(13,33)/(groebnerMatrix(13,32)); groebnerMatrix(18,43) = (groebnerMatrix(13,43)/(groebnerMatrix(13,32))-groebnerMatrix(15,75)/(groebnerMatrix(15,71))); groebnerMatrix(18,44) = groebnerMatrix(13,44)/(groebnerMatrix(13,32)); groebnerMatrix(18,47) = (groebnerMatrix(13,47)/(groebnerMatrix(13,32))-groebnerMatrix(15,76)/(groebnerMatrix(15,71))); groebnerMatrix(18,48) = groebnerMatrix(13,48)/(groebnerMatrix(13,32)); groebnerMatrix(18,52) = (groebnerMatrix(13,52)/(groebnerMatrix(13,32))-groebnerMatrix(15,77)/(groebnerMatrix(15,71))); groebnerMatrix(18,53) = groebnerMatrix(13,53)/(groebnerMatrix(13,32)); groebnerMatrix(18,64) = (groebnerMatrix(13,64)/(groebnerMatrix(13,32))-groebnerMatrix(15,81)/(groebnerMatrix(15,71))); groebnerMatrix(18,65) = groebnerMatrix(13,65)/(groebnerMatrix(13,32)); groebnerMatrix(18,68) = (groebnerMatrix(13,68)/(groebnerMatrix(13,32))-groebnerMatrix(15,82)/(groebnerMatrix(15,71))); groebnerMatrix(18,69) = groebnerMatrix(13,69)/(groebnerMatrix(13,32)); groebnerMatrix(18,71) = groebnerMatrix(13,71)/(groebnerMatrix(13,32)); groebnerMatrix(18,73) = (groebnerMatrix(13,73)/(groebnerMatrix(13,32))-groebnerMatrix(15,83)/(groebnerMatrix(15,71))); groebnerMatrix(18,74) = groebnerMatrix(13,74)/(groebnerMatrix(13,32)); groebnerMatrix(18,75) = groebnerMatrix(13,75)/(groebnerMatrix(13,32)); groebnerMatrix(18,76) = groebnerMatrix(13,76)/(groebnerMatrix(13,32)); groebnerMatrix(18,77) = groebnerMatrix(13,77)/(groebnerMatrix(13,32)); groebnerMatrix(18,79) = (groebnerMatrix(13,79)/(groebnerMatrix(13,32))-groebnerMatrix(15,84)/(groebnerMatrix(15,71))); groebnerMatrix(18,80) = groebnerMatrix(13,80)/(groebnerMatrix(13,32)); groebnerMatrix(18,81) = groebnerMatrix(13,81)/(groebnerMatrix(13,32)); groebnerMatrix(18,82) = groebnerMatrix(13,82)/(groebnerMatrix(13,32)); groebnerMatrix(18,83) = groebnerMatrix(13,83)/(groebnerMatrix(13,32)); groebnerMatrix(18,84) = groebnerMatrix(13,84)/(groebnerMatrix(13,32)); } void opengv::absolute_pose::modules::gp3p::sPolynomial19( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(19,34) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(12,71)/(groebnerMatrix(12,70))); groebnerMatrix(19,35) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(19,45) = -groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(19,49) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(12,76)/(groebnerMatrix(12,70))); groebnerMatrix(19,50) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(19,54) = -groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(19,55) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(19,66) = -groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(19,70) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(12,82)/(groebnerMatrix(12,70))); groebnerMatrix(19,71) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(19,75) = -groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(19,76) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(19,81) = -groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(19,82) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); } void opengv::absolute_pose::modules::gp3p::sPolynomial20( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(20,21) = groebnerMatrix(8,21)/(groebnerMatrix(8,19)); groebnerMatrix(20,28) = -groebnerMatrix(10,70)/(groebnerMatrix(10,66)); groebnerMatrix(20,31) = (groebnerMatrix(8,31)/(groebnerMatrix(8,19))-groebnerMatrix(10,71)/(groebnerMatrix(10,66))); groebnerMatrix(20,33) = groebnerMatrix(8,33)/(groebnerMatrix(8,19)); groebnerMatrix(20,42) = -groebnerMatrix(10,75)/(groebnerMatrix(10,66)); groebnerMatrix(20,46) = -groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(20,51) = (groebnerMatrix(8,51)/(groebnerMatrix(8,19))-groebnerMatrix(10,77)/(groebnerMatrix(10,66))); groebnerMatrix(20,53) = groebnerMatrix(8,53)/(groebnerMatrix(8,19)); groebnerMatrix(20,63) = -groebnerMatrix(10,81)/(groebnerMatrix(10,66)); groebnerMatrix(20,66) = groebnerMatrix(8,66)/(groebnerMatrix(8,19)); groebnerMatrix(20,67) = -groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(20,70) = groebnerMatrix(8,70)/(groebnerMatrix(8,19)); groebnerMatrix(20,71) = groebnerMatrix(8,71)/(groebnerMatrix(8,19)); groebnerMatrix(20,72) = -groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(20,75) = groebnerMatrix(8,75)/(groebnerMatrix(8,19)); groebnerMatrix(20,77) = groebnerMatrix(8,77)/(groebnerMatrix(8,19)); groebnerMatrix(20,78) = (groebnerMatrix(8,78)/(groebnerMatrix(8,19))-groebnerMatrix(10,84)/(groebnerMatrix(10,66))); groebnerMatrix(20,80) = groebnerMatrix(8,80)/(groebnerMatrix(8,19)); groebnerMatrix(20,82) = groebnerMatrix(8,82)/(groebnerMatrix(8,19)); groebnerMatrix(20,83) = groebnerMatrix(8,83)/(groebnerMatrix(8,19)); groebnerMatrix(20,84) = groebnerMatrix(8,84)/(groebnerMatrix(8,19)); } void opengv::absolute_pose::modules::gp3p::sPolynomial21( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(21,11) = (groebnerMatrix(16,55)/(groebnerMatrix(16,54))-groebnerMatrix(17,48)/(groebnerMatrix(17,44))); groebnerMatrix(21,14) = (groebnerMatrix(16,56)/(groebnerMatrix(16,54))-groebnerMatrix(17,53)/(groebnerMatrix(17,44))); groebnerMatrix(21,44) = (groebnerMatrix(16,75)/(groebnerMatrix(16,54))-groebnerMatrix(17,65)/(groebnerMatrix(17,44))); groebnerMatrix(21,48) = (groebnerMatrix(16,76)/(groebnerMatrix(16,54))-groebnerMatrix(17,69)/(groebnerMatrix(17,44))); groebnerMatrix(21,53) = (groebnerMatrix(16,77)/(groebnerMatrix(16,54))-groebnerMatrix(17,74)/(groebnerMatrix(17,44))); groebnerMatrix(21,54) = -groebnerMatrix(17,75)/(groebnerMatrix(17,44)); groebnerMatrix(21,55) = -groebnerMatrix(17,76)/(groebnerMatrix(17,44)); groebnerMatrix(21,56) = -groebnerMatrix(17,77)/(groebnerMatrix(17,44)); groebnerMatrix(21,65) = groebnerMatrix(16,81)/(groebnerMatrix(16,54)); groebnerMatrix(21,69) = groebnerMatrix(16,82)/(groebnerMatrix(16,54)); groebnerMatrix(21,74) = (groebnerMatrix(16,83)/(groebnerMatrix(16,54))-groebnerMatrix(17,80)/(groebnerMatrix(17,44))); groebnerMatrix(21,75) = -groebnerMatrix(17,81)/(groebnerMatrix(17,44)); groebnerMatrix(21,76) = -groebnerMatrix(17,82)/(groebnerMatrix(17,44)); groebnerMatrix(21,77) = -groebnerMatrix(17,83)/(groebnerMatrix(17,44)); groebnerMatrix(21,80) = groebnerMatrix(16,84)/(groebnerMatrix(16,54)); groebnerMatrix(21,83) = -groebnerMatrix(17,84)/(groebnerMatrix(17,44)); } void opengv::absolute_pose::modules::gp3p::sPolynomial22( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(22,10) = (groebnerMatrix(16,55)/(groebnerMatrix(16,54))-groebnerMatrix(18,47)/(groebnerMatrix(18,43))); groebnerMatrix(22,13) = (groebnerMatrix(16,56)/(groebnerMatrix(16,54))-groebnerMatrix(18,52)/(groebnerMatrix(18,43))); groebnerMatrix(22,43) = (groebnerMatrix(16,75)/(groebnerMatrix(16,54))-groebnerMatrix(18,64)/(groebnerMatrix(18,43))); groebnerMatrix(22,47) = (groebnerMatrix(16,76)/(groebnerMatrix(16,54))-groebnerMatrix(18,68)/(groebnerMatrix(18,43))); groebnerMatrix(22,52) = (groebnerMatrix(16,77)/(groebnerMatrix(16,54))-groebnerMatrix(18,73)/(groebnerMatrix(18,43))); groebnerMatrix(22,54) = -groebnerMatrix(18,75)/(groebnerMatrix(18,43)); groebnerMatrix(22,55) = -groebnerMatrix(18,76)/(groebnerMatrix(18,43)); groebnerMatrix(22,56) = -groebnerMatrix(18,77)/(groebnerMatrix(18,43)); groebnerMatrix(22,64) = groebnerMatrix(16,81)/(groebnerMatrix(16,54)); groebnerMatrix(22,68) = groebnerMatrix(16,82)/(groebnerMatrix(16,54)); groebnerMatrix(22,73) = (groebnerMatrix(16,83)/(groebnerMatrix(16,54))-groebnerMatrix(18,79)/(groebnerMatrix(18,43))); groebnerMatrix(22,75) = -groebnerMatrix(18,81)/(groebnerMatrix(18,43)); groebnerMatrix(22,76) = -groebnerMatrix(18,82)/(groebnerMatrix(18,43)); groebnerMatrix(22,77) = -groebnerMatrix(18,83)/(groebnerMatrix(18,43)); groebnerMatrix(22,79) = groebnerMatrix(16,84)/(groebnerMatrix(16,54)); groebnerMatrix(22,83) = -groebnerMatrix(18,84)/(groebnerMatrix(18,43)); } void opengv::absolute_pose::modules::gp3p::sPolynomial23( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(23,9) = (groebnerMatrix(16,55)/(groebnerMatrix(16,54))-groebnerMatrix(20,46)/(groebnerMatrix(20,42))); groebnerMatrix(23,12) = (groebnerMatrix(16,56)/(groebnerMatrix(16,54))-groebnerMatrix(20,51)/(groebnerMatrix(20,42))); groebnerMatrix(23,42) = (groebnerMatrix(16,75)/(groebnerMatrix(16,54))-groebnerMatrix(20,63)/(groebnerMatrix(20,42))); groebnerMatrix(23,46) = (groebnerMatrix(16,76)/(groebnerMatrix(16,54))-groebnerMatrix(20,67)/(groebnerMatrix(20,42))); groebnerMatrix(23,51) = (groebnerMatrix(16,77)/(groebnerMatrix(16,54))-groebnerMatrix(20,72)/(groebnerMatrix(20,42))); groebnerMatrix(23,54) = -groebnerMatrix(20,75)/(groebnerMatrix(20,42)); groebnerMatrix(23,55) = -groebnerMatrix(20,76)/(groebnerMatrix(20,42)); groebnerMatrix(23,56) = -groebnerMatrix(20,77)/(groebnerMatrix(20,42)); groebnerMatrix(23,63) = groebnerMatrix(16,81)/(groebnerMatrix(16,54)); groebnerMatrix(23,67) = groebnerMatrix(16,82)/(groebnerMatrix(16,54)); groebnerMatrix(23,72) = (groebnerMatrix(16,83)/(groebnerMatrix(16,54))-groebnerMatrix(20,78)/(groebnerMatrix(20,42))); groebnerMatrix(23,75) = -groebnerMatrix(20,81)/(groebnerMatrix(20,42)); groebnerMatrix(23,76) = -groebnerMatrix(20,82)/(groebnerMatrix(20,42)); groebnerMatrix(23,77) = -groebnerMatrix(20,83)/(groebnerMatrix(20,42)); groebnerMatrix(23,78) = groebnerMatrix(16,84)/(groebnerMatrix(16,54)); groebnerMatrix(23,83) = -groebnerMatrix(20,84)/(groebnerMatrix(20,42)); } void opengv::absolute_pose::modules::gp3p::sPolynomial24( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(24,5) = (groebnerMatrix(12,71)/(groebnerMatrix(12,70))-groebnerMatrix(17,48)/(groebnerMatrix(17,44))); groebnerMatrix(24,8) = groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(24,11) = (groebnerMatrix(12,76)/(groebnerMatrix(12,70))-groebnerMatrix(17,53)/(groebnerMatrix(17,44))); groebnerMatrix(24,14) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(24,30) = -groebnerMatrix(17,65)/(groebnerMatrix(17,44)); groebnerMatrix(24,33) = -groebnerMatrix(17,69)/(groebnerMatrix(17,44)); groebnerMatrix(24,44) = groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(24,48) = (groebnerMatrix(12,82)/(groebnerMatrix(12,70))-groebnerMatrix(17,74)/(groebnerMatrix(17,44))); groebnerMatrix(24,49) = -groebnerMatrix(17,75)/(groebnerMatrix(17,44)); groebnerMatrix(24,50) = -groebnerMatrix(17,76)/(groebnerMatrix(17,44)); groebnerMatrix(24,53) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(24,55) = -groebnerMatrix(17,77)/(groebnerMatrix(17,44)); groebnerMatrix(24,69) = -groebnerMatrix(17,80)/(groebnerMatrix(17,44)); groebnerMatrix(24,70) = -groebnerMatrix(17,81)/(groebnerMatrix(17,44)); groebnerMatrix(24,71) = -groebnerMatrix(17,82)/(groebnerMatrix(17,44)); groebnerMatrix(24,74) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(24,76) = -groebnerMatrix(17,83)/(groebnerMatrix(17,44)); groebnerMatrix(24,82) = -groebnerMatrix(17,84)/(groebnerMatrix(17,44)); } void opengv::absolute_pose::modules::gp3p::sPolynomial25( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(25,4) = (groebnerMatrix(12,71)/(groebnerMatrix(12,70))-groebnerMatrix(18,47)/(groebnerMatrix(18,43))); groebnerMatrix(25,7) = groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(25,10) = (groebnerMatrix(12,76)/(groebnerMatrix(12,70))-groebnerMatrix(18,52)/(groebnerMatrix(18,43))); groebnerMatrix(25,13) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(25,29) = -groebnerMatrix(18,64)/(groebnerMatrix(18,43)); groebnerMatrix(25,32) = -groebnerMatrix(18,68)/(groebnerMatrix(18,43)); groebnerMatrix(25,43) = groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(25,47) = (groebnerMatrix(12,82)/(groebnerMatrix(12,70))-groebnerMatrix(18,73)/(groebnerMatrix(18,43))); groebnerMatrix(25,49) = -groebnerMatrix(18,75)/(groebnerMatrix(18,43)); groebnerMatrix(25,50) = -groebnerMatrix(18,76)/(groebnerMatrix(18,43)); groebnerMatrix(25,52) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(25,55) = -groebnerMatrix(18,77)/(groebnerMatrix(18,43)); groebnerMatrix(25,68) = -groebnerMatrix(18,79)/(groebnerMatrix(18,43)); groebnerMatrix(25,70) = -groebnerMatrix(18,81)/(groebnerMatrix(18,43)); groebnerMatrix(25,71) = -groebnerMatrix(18,82)/(groebnerMatrix(18,43)); groebnerMatrix(25,73) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(25,76) = -groebnerMatrix(18,83)/(groebnerMatrix(18,43)); groebnerMatrix(25,82) = -groebnerMatrix(18,84)/(groebnerMatrix(18,43)); } void opengv::absolute_pose::modules::gp3p::sPolynomial26( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(26,3) = (groebnerMatrix(12,71)/(groebnerMatrix(12,70))-groebnerMatrix(20,46)/(groebnerMatrix(20,42))); groebnerMatrix(26,6) = groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(26,9) = (groebnerMatrix(12,76)/(groebnerMatrix(12,70))-groebnerMatrix(20,51)/(groebnerMatrix(20,42))); groebnerMatrix(26,12) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(26,28) = -groebnerMatrix(20,63)/(groebnerMatrix(20,42)); groebnerMatrix(26,31) = -groebnerMatrix(20,67)/(groebnerMatrix(20,42)); groebnerMatrix(26,42) = groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(26,46) = (groebnerMatrix(12,82)/(groebnerMatrix(12,70))-groebnerMatrix(20,72)/(groebnerMatrix(20,42))); groebnerMatrix(26,49) = -groebnerMatrix(20,75)/(groebnerMatrix(20,42)); groebnerMatrix(26,50) = -groebnerMatrix(20,76)/(groebnerMatrix(20,42)); groebnerMatrix(26,51) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(26,55) = -groebnerMatrix(20,77)/(groebnerMatrix(20,42)); groebnerMatrix(26,67) = -groebnerMatrix(20,78)/(groebnerMatrix(20,42)); groebnerMatrix(26,70) = -groebnerMatrix(20,81)/(groebnerMatrix(20,42)); groebnerMatrix(26,71) = -groebnerMatrix(20,82)/(groebnerMatrix(20,42)); groebnerMatrix(26,72) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(26,76) = -groebnerMatrix(20,83)/(groebnerMatrix(20,42)); groebnerMatrix(26,82) = -groebnerMatrix(20,84)/(groebnerMatrix(20,42)); } void opengv::absolute_pose::modules::gp3p::sPolynomial27( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(27,2) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(17,48)/(groebnerMatrix(17,44))); groebnerMatrix(27,5) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(27,8) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(17,53)/(groebnerMatrix(17,44))); groebnerMatrix(27,11) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(27,14) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(27,21) = -groebnerMatrix(17,65)/(groebnerMatrix(17,44)); groebnerMatrix(27,30) = -groebnerMatrix(17,69)/(groebnerMatrix(17,44)); groebnerMatrix(27,44) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(17,74)/(groebnerMatrix(17,44))); groebnerMatrix(27,45) = -groebnerMatrix(17,75)/(groebnerMatrix(17,44)); groebnerMatrix(27,48) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(27,49) = -groebnerMatrix(17,76)/(groebnerMatrix(17,44)); groebnerMatrix(27,53) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(27,54) = -groebnerMatrix(17,77)/(groebnerMatrix(17,44)); groebnerMatrix(27,65) = -groebnerMatrix(17,80)/(groebnerMatrix(17,44)); groebnerMatrix(27,66) = -groebnerMatrix(17,81)/(groebnerMatrix(17,44)); groebnerMatrix(27,70) = -groebnerMatrix(17,82)/(groebnerMatrix(17,44)); groebnerMatrix(27,74) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); groebnerMatrix(27,75) = -groebnerMatrix(17,83)/(groebnerMatrix(17,44)); groebnerMatrix(27,81) = -groebnerMatrix(17,84)/(groebnerMatrix(17,44)); } void opengv::absolute_pose::modules::gp3p::sPolynomial28( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(28,1) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(18,47)/(groebnerMatrix(18,43))); groebnerMatrix(28,4) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(28,7) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(18,52)/(groebnerMatrix(18,43))); groebnerMatrix(28,10) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(28,13) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(28,20) = -groebnerMatrix(18,64)/(groebnerMatrix(18,43)); groebnerMatrix(28,29) = -groebnerMatrix(18,68)/(groebnerMatrix(18,43)); groebnerMatrix(28,43) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(18,73)/(groebnerMatrix(18,43))); groebnerMatrix(28,45) = -groebnerMatrix(18,75)/(groebnerMatrix(18,43)); groebnerMatrix(28,47) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(28,49) = -groebnerMatrix(18,76)/(groebnerMatrix(18,43)); groebnerMatrix(28,52) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(28,54) = -groebnerMatrix(18,77)/(groebnerMatrix(18,43)); groebnerMatrix(28,64) = -groebnerMatrix(18,79)/(groebnerMatrix(18,43)); groebnerMatrix(28,66) = -groebnerMatrix(18,81)/(groebnerMatrix(18,43)); groebnerMatrix(28,70) = -groebnerMatrix(18,82)/(groebnerMatrix(18,43)); groebnerMatrix(28,73) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); groebnerMatrix(28,75) = -groebnerMatrix(18,83)/(groebnerMatrix(18,43)); groebnerMatrix(28,81) = -groebnerMatrix(18,84)/(groebnerMatrix(18,43)); } void opengv::absolute_pose::modules::gp3p::sPolynomial29( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(29,0) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(20,46)/(groebnerMatrix(20,42))); groebnerMatrix(29,3) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(29,6) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(20,51)/(groebnerMatrix(20,42))); groebnerMatrix(29,9) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(29,12) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(29,19) = -groebnerMatrix(20,63)/(groebnerMatrix(20,42)); groebnerMatrix(29,28) = -groebnerMatrix(20,67)/(groebnerMatrix(20,42)); groebnerMatrix(29,42) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(20,72)/(groebnerMatrix(20,42))); groebnerMatrix(29,45) = -groebnerMatrix(20,75)/(groebnerMatrix(20,42)); groebnerMatrix(29,46) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(29,49) = -groebnerMatrix(20,76)/(groebnerMatrix(20,42)); groebnerMatrix(29,51) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(29,54) = -groebnerMatrix(20,77)/(groebnerMatrix(20,42)); groebnerMatrix(29,63) = -groebnerMatrix(20,78)/(groebnerMatrix(20,42)); groebnerMatrix(29,66) = -groebnerMatrix(20,81)/(groebnerMatrix(20,42)); groebnerMatrix(29,70) = -groebnerMatrix(20,82)/(groebnerMatrix(20,42)); groebnerMatrix(29,72) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); groebnerMatrix(29,75) = -groebnerMatrix(20,83)/(groebnerMatrix(20,42)); groebnerMatrix(29,81) = -groebnerMatrix(20,84)/(groebnerMatrix(20,42)); } void opengv::absolute_pose::modules::gp3p::sPolynomial30( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(30,43) = groebnerMatrix(17,75)/(groebnerMatrix(17,44)); groebnerMatrix(30,44) = -groebnerMatrix(18,75)/(groebnerMatrix(18,43)); groebnerMatrix(30,47) = groebnerMatrix(17,76)/(groebnerMatrix(17,44)); groebnerMatrix(30,48) = -groebnerMatrix(18,76)/(groebnerMatrix(18,43)); groebnerMatrix(30,52) = groebnerMatrix(17,77)/(groebnerMatrix(17,44)); groebnerMatrix(30,53) = -groebnerMatrix(18,77)/(groebnerMatrix(18,43)); groebnerMatrix(30,64) = groebnerMatrix(17,81)/(groebnerMatrix(17,44)); groebnerMatrix(30,65) = -groebnerMatrix(18,81)/(groebnerMatrix(18,43)); groebnerMatrix(30,68) = groebnerMatrix(17,82)/(groebnerMatrix(17,44)); groebnerMatrix(30,69) = -groebnerMatrix(18,82)/(groebnerMatrix(18,43)); groebnerMatrix(30,73) = groebnerMatrix(17,83)/(groebnerMatrix(17,44)); groebnerMatrix(30,74) = -groebnerMatrix(18,83)/(groebnerMatrix(18,43)); groebnerMatrix(30,79) = groebnerMatrix(17,84)/(groebnerMatrix(17,44)); groebnerMatrix(30,80) = -groebnerMatrix(18,84)/(groebnerMatrix(18,43)); } void opengv::absolute_pose::modules::gp3p::sPolynomial31( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(31,42) = groebnerMatrix(17,75)/(groebnerMatrix(17,44)); groebnerMatrix(31,44) = -groebnerMatrix(20,75)/(groebnerMatrix(20,42)); groebnerMatrix(31,46) = groebnerMatrix(17,76)/(groebnerMatrix(17,44)); groebnerMatrix(31,48) = -groebnerMatrix(20,76)/(groebnerMatrix(20,42)); groebnerMatrix(31,51) = groebnerMatrix(17,77)/(groebnerMatrix(17,44)); groebnerMatrix(31,53) = -groebnerMatrix(20,77)/(groebnerMatrix(20,42)); groebnerMatrix(31,63) = groebnerMatrix(17,81)/(groebnerMatrix(17,44)); groebnerMatrix(31,65) = -groebnerMatrix(20,81)/(groebnerMatrix(20,42)); groebnerMatrix(31,67) = groebnerMatrix(17,82)/(groebnerMatrix(17,44)); groebnerMatrix(31,69) = -groebnerMatrix(20,82)/(groebnerMatrix(20,42)); groebnerMatrix(31,72) = groebnerMatrix(17,83)/(groebnerMatrix(17,44)); groebnerMatrix(31,74) = -groebnerMatrix(20,83)/(groebnerMatrix(20,42)); groebnerMatrix(31,78) = groebnerMatrix(17,84)/(groebnerMatrix(17,44)); groebnerMatrix(31,80) = -groebnerMatrix(20,84)/(groebnerMatrix(20,42)); } void opengv::absolute_pose::modules::gp3p::sPolynomial32( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(32,42) = groebnerMatrix(18,75)/(groebnerMatrix(18,43)); groebnerMatrix(32,43) = -groebnerMatrix(20,75)/(groebnerMatrix(20,42)); groebnerMatrix(32,46) = groebnerMatrix(18,76)/(groebnerMatrix(18,43)); groebnerMatrix(32,47) = -groebnerMatrix(20,76)/(groebnerMatrix(20,42)); groebnerMatrix(32,51) = groebnerMatrix(18,77)/(groebnerMatrix(18,43)); groebnerMatrix(32,52) = -groebnerMatrix(20,77)/(groebnerMatrix(20,42)); groebnerMatrix(32,63) = groebnerMatrix(18,81)/(groebnerMatrix(18,43)); groebnerMatrix(32,64) = -groebnerMatrix(20,81)/(groebnerMatrix(20,42)); groebnerMatrix(32,67) = groebnerMatrix(18,82)/(groebnerMatrix(18,43)); groebnerMatrix(32,68) = -groebnerMatrix(20,82)/(groebnerMatrix(20,42)); groebnerMatrix(32,72) = groebnerMatrix(18,83)/(groebnerMatrix(18,43)); groebnerMatrix(32,73) = -groebnerMatrix(20,83)/(groebnerMatrix(20,42)); groebnerMatrix(32,78) = groebnerMatrix(18,84)/(groebnerMatrix(18,43)); groebnerMatrix(32,79) = -groebnerMatrix(20,84)/(groebnerMatrix(20,42)); } void opengv::absolute_pose::modules::gp3p::sPolynomial33( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(33,46) = -groebnerMatrix(32,67)/(groebnerMatrix(32,65)); groebnerMatrix(33,47) = -groebnerMatrix(32,68)/(groebnerMatrix(32,65)); groebnerMatrix(33,48) = (groebnerMatrix(17,48)/(groebnerMatrix(17,44))-groebnerMatrix(32,69)/(groebnerMatrix(32,65))); groebnerMatrix(33,51) = -groebnerMatrix(32,72)/(groebnerMatrix(32,65)); groebnerMatrix(33,52) = -groebnerMatrix(32,73)/(groebnerMatrix(32,65)); groebnerMatrix(33,53) = (groebnerMatrix(17,53)/(groebnerMatrix(17,44))-groebnerMatrix(32,74)/(groebnerMatrix(32,65))); groebnerMatrix(33,54) = -groebnerMatrix(32,75)/(groebnerMatrix(32,65)); groebnerMatrix(33,55) = -groebnerMatrix(32,76)/(groebnerMatrix(32,65)); groebnerMatrix(33,56) = -groebnerMatrix(32,77)/(groebnerMatrix(32,65)); groebnerMatrix(33,65) = groebnerMatrix(17,65)/(groebnerMatrix(17,44)); groebnerMatrix(33,69) = groebnerMatrix(17,69)/(groebnerMatrix(17,44)); groebnerMatrix(33,72) = -groebnerMatrix(32,78)/(groebnerMatrix(32,65)); groebnerMatrix(33,73) = -groebnerMatrix(32,79)/(groebnerMatrix(32,65)); groebnerMatrix(33,74) = (groebnerMatrix(17,74)/(groebnerMatrix(17,44))-groebnerMatrix(32,80)/(groebnerMatrix(32,65))); groebnerMatrix(33,75) = (groebnerMatrix(17,75)/(groebnerMatrix(17,44))-groebnerMatrix(32,81)/(groebnerMatrix(32,65))); groebnerMatrix(33,76) = (groebnerMatrix(17,76)/(groebnerMatrix(17,44))-groebnerMatrix(32,82)/(groebnerMatrix(32,65))); groebnerMatrix(33,77) = (groebnerMatrix(17,77)/(groebnerMatrix(17,44))-groebnerMatrix(32,83)/(groebnerMatrix(32,65))); groebnerMatrix(33,80) = groebnerMatrix(17,80)/(groebnerMatrix(17,44)); groebnerMatrix(33,81) = groebnerMatrix(17,81)/(groebnerMatrix(17,44)); groebnerMatrix(33,82) = groebnerMatrix(17,82)/(groebnerMatrix(17,44)); groebnerMatrix(33,83) = (groebnerMatrix(17,83)/(groebnerMatrix(17,44))-groebnerMatrix(32,84)/(groebnerMatrix(32,65))); groebnerMatrix(33,84) = groebnerMatrix(17,84)/(groebnerMatrix(17,44)); } void opengv::absolute_pose::modules::gp3p::sPolynomial34( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(34,44) = -groebnerMatrix(30,65)/(groebnerMatrix(30,64)); groebnerMatrix(34,47) = (groebnerMatrix(18,47)/(groebnerMatrix(18,43))-groebnerMatrix(30,68)/(groebnerMatrix(30,64))); groebnerMatrix(34,48) = -groebnerMatrix(30,69)/(groebnerMatrix(30,64)); groebnerMatrix(34,52) = (groebnerMatrix(18,52)/(groebnerMatrix(18,43))-groebnerMatrix(30,73)/(groebnerMatrix(30,64))); groebnerMatrix(34,53) = -groebnerMatrix(30,74)/(groebnerMatrix(30,64)); groebnerMatrix(34,54) = -groebnerMatrix(30,75)/(groebnerMatrix(30,64)); groebnerMatrix(34,55) = -groebnerMatrix(30,76)/(groebnerMatrix(30,64)); groebnerMatrix(34,56) = -groebnerMatrix(30,77)/(groebnerMatrix(30,64)); groebnerMatrix(34,64) = groebnerMatrix(18,64)/(groebnerMatrix(18,43)); groebnerMatrix(34,68) = groebnerMatrix(18,68)/(groebnerMatrix(18,43)); groebnerMatrix(34,73) = (groebnerMatrix(18,73)/(groebnerMatrix(18,43))-groebnerMatrix(30,79)/(groebnerMatrix(30,64))); groebnerMatrix(34,74) = -groebnerMatrix(30,80)/(groebnerMatrix(30,64)); groebnerMatrix(34,75) = (groebnerMatrix(18,75)/(groebnerMatrix(18,43))-groebnerMatrix(30,81)/(groebnerMatrix(30,64))); groebnerMatrix(34,76) = (groebnerMatrix(18,76)/(groebnerMatrix(18,43))-groebnerMatrix(30,82)/(groebnerMatrix(30,64))); groebnerMatrix(34,77) = (groebnerMatrix(18,77)/(groebnerMatrix(18,43))-groebnerMatrix(30,83)/(groebnerMatrix(30,64))); groebnerMatrix(34,79) = groebnerMatrix(18,79)/(groebnerMatrix(18,43)); groebnerMatrix(34,81) = groebnerMatrix(18,81)/(groebnerMatrix(18,43)); groebnerMatrix(34,82) = groebnerMatrix(18,82)/(groebnerMatrix(18,43)); groebnerMatrix(34,83) = (groebnerMatrix(18,83)/(groebnerMatrix(18,43))-groebnerMatrix(30,84)/(groebnerMatrix(30,64))); groebnerMatrix(34,84) = groebnerMatrix(18,84)/(groebnerMatrix(18,43)); } void opengv::absolute_pose::modules::gp3p::sPolynomial35( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(35,44) = -groebnerMatrix(31,65)/(groebnerMatrix(31,63)); groebnerMatrix(35,46) = (groebnerMatrix(20,46)/(groebnerMatrix(20,42))-groebnerMatrix(31,67)/(groebnerMatrix(31,63))); groebnerMatrix(35,48) = -groebnerMatrix(31,69)/(groebnerMatrix(31,63)); groebnerMatrix(35,51) = (groebnerMatrix(20,51)/(groebnerMatrix(20,42))-groebnerMatrix(31,72)/(groebnerMatrix(31,63))); groebnerMatrix(35,53) = -groebnerMatrix(31,74)/(groebnerMatrix(31,63)); groebnerMatrix(35,54) = -groebnerMatrix(31,75)/(groebnerMatrix(31,63)); groebnerMatrix(35,55) = -groebnerMatrix(31,76)/(groebnerMatrix(31,63)); groebnerMatrix(35,56) = -groebnerMatrix(31,77)/(groebnerMatrix(31,63)); groebnerMatrix(35,63) = groebnerMatrix(20,63)/(groebnerMatrix(20,42)); groebnerMatrix(35,67) = groebnerMatrix(20,67)/(groebnerMatrix(20,42)); groebnerMatrix(35,72) = (groebnerMatrix(20,72)/(groebnerMatrix(20,42))-groebnerMatrix(31,78)/(groebnerMatrix(31,63))); groebnerMatrix(35,74) = -groebnerMatrix(31,80)/(groebnerMatrix(31,63)); groebnerMatrix(35,75) = (groebnerMatrix(20,75)/(groebnerMatrix(20,42))-groebnerMatrix(31,81)/(groebnerMatrix(31,63))); groebnerMatrix(35,76) = (groebnerMatrix(20,76)/(groebnerMatrix(20,42))-groebnerMatrix(31,82)/(groebnerMatrix(31,63))); groebnerMatrix(35,77) = (groebnerMatrix(20,77)/(groebnerMatrix(20,42))-groebnerMatrix(31,83)/(groebnerMatrix(31,63))); groebnerMatrix(35,78) = groebnerMatrix(20,78)/(groebnerMatrix(20,42)); groebnerMatrix(35,81) = groebnerMatrix(20,81)/(groebnerMatrix(20,42)); groebnerMatrix(35,82) = groebnerMatrix(20,82)/(groebnerMatrix(20,42)); groebnerMatrix(35,83) = (groebnerMatrix(20,83)/(groebnerMatrix(20,42))-groebnerMatrix(31,84)/(groebnerMatrix(31,63))); groebnerMatrix(35,84) = groebnerMatrix(20,84)/(groebnerMatrix(20,42)); } void opengv::absolute_pose::modules::gp3p::sPolynomial36( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(36,31) = -groebnerMatrix(32,67)/(groebnerMatrix(32,65)); groebnerMatrix(36,32) = -groebnerMatrix(32,68)/(groebnerMatrix(32,65)); groebnerMatrix(36,33) = (groebnerMatrix(12,71)/(groebnerMatrix(12,70))-groebnerMatrix(32,69)/(groebnerMatrix(32,65))); groebnerMatrix(36,44) = groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(36,46) = -groebnerMatrix(32,72)/(groebnerMatrix(32,65)); groebnerMatrix(36,47) = -groebnerMatrix(32,73)/(groebnerMatrix(32,65)); groebnerMatrix(36,48) = (groebnerMatrix(12,76)/(groebnerMatrix(12,70))-groebnerMatrix(32,74)/(groebnerMatrix(32,65))); groebnerMatrix(36,49) = -groebnerMatrix(32,75)/(groebnerMatrix(32,65)); groebnerMatrix(36,50) = -groebnerMatrix(32,76)/(groebnerMatrix(32,65)); groebnerMatrix(36,53) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(36,55) = -groebnerMatrix(32,77)/(groebnerMatrix(32,65)); groebnerMatrix(36,65) = groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(36,67) = -groebnerMatrix(32,78)/(groebnerMatrix(32,65)); groebnerMatrix(36,68) = -groebnerMatrix(32,79)/(groebnerMatrix(32,65)); groebnerMatrix(36,69) = (groebnerMatrix(12,82)/(groebnerMatrix(12,70))-groebnerMatrix(32,80)/(groebnerMatrix(32,65))); groebnerMatrix(36,70) = -groebnerMatrix(32,81)/(groebnerMatrix(32,65)); groebnerMatrix(36,71) = -groebnerMatrix(32,82)/(groebnerMatrix(32,65)); groebnerMatrix(36,74) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(36,76) = -groebnerMatrix(32,83)/(groebnerMatrix(32,65)); groebnerMatrix(36,80) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(36,82) = -groebnerMatrix(32,84)/(groebnerMatrix(32,65)); } void opengv::absolute_pose::modules::gp3p::sPolynomial37( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(37,30) = -groebnerMatrix(30,65)/(groebnerMatrix(30,64)); groebnerMatrix(37,32) = (groebnerMatrix(12,71)/(groebnerMatrix(12,70))-groebnerMatrix(30,68)/(groebnerMatrix(30,64))); groebnerMatrix(37,33) = -groebnerMatrix(30,69)/(groebnerMatrix(30,64)); groebnerMatrix(37,43) = groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(37,47) = (groebnerMatrix(12,76)/(groebnerMatrix(12,70))-groebnerMatrix(30,73)/(groebnerMatrix(30,64))); groebnerMatrix(37,48) = -groebnerMatrix(30,74)/(groebnerMatrix(30,64)); groebnerMatrix(37,49) = -groebnerMatrix(30,75)/(groebnerMatrix(30,64)); groebnerMatrix(37,50) = -groebnerMatrix(30,76)/(groebnerMatrix(30,64)); groebnerMatrix(37,52) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(37,55) = -groebnerMatrix(30,77)/(groebnerMatrix(30,64)); groebnerMatrix(37,64) = groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(37,68) = (groebnerMatrix(12,82)/(groebnerMatrix(12,70))-groebnerMatrix(30,79)/(groebnerMatrix(30,64))); groebnerMatrix(37,69) = -groebnerMatrix(30,80)/(groebnerMatrix(30,64)); groebnerMatrix(37,70) = -groebnerMatrix(30,81)/(groebnerMatrix(30,64)); groebnerMatrix(37,71) = -groebnerMatrix(30,82)/(groebnerMatrix(30,64)); groebnerMatrix(37,73) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(37,76) = -groebnerMatrix(30,83)/(groebnerMatrix(30,64)); groebnerMatrix(37,79) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(37,82) = -groebnerMatrix(30,84)/(groebnerMatrix(30,64)); } void opengv::absolute_pose::modules::gp3p::sPolynomial38( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(38,30) = -groebnerMatrix(31,65)/(groebnerMatrix(31,63)); groebnerMatrix(38,31) = (groebnerMatrix(12,71)/(groebnerMatrix(12,70))-groebnerMatrix(31,67)/(groebnerMatrix(31,63))); groebnerMatrix(38,33) = -groebnerMatrix(31,69)/(groebnerMatrix(31,63)); groebnerMatrix(38,42) = groebnerMatrix(12,75)/(groebnerMatrix(12,70)); groebnerMatrix(38,46) = (groebnerMatrix(12,76)/(groebnerMatrix(12,70))-groebnerMatrix(31,72)/(groebnerMatrix(31,63))); groebnerMatrix(38,48) = -groebnerMatrix(31,74)/(groebnerMatrix(31,63)); groebnerMatrix(38,49) = -groebnerMatrix(31,75)/(groebnerMatrix(31,63)); groebnerMatrix(38,50) = -groebnerMatrix(31,76)/(groebnerMatrix(31,63)); groebnerMatrix(38,51) = groebnerMatrix(12,77)/(groebnerMatrix(12,70)); groebnerMatrix(38,55) = -groebnerMatrix(31,77)/(groebnerMatrix(31,63)); groebnerMatrix(38,63) = groebnerMatrix(12,81)/(groebnerMatrix(12,70)); groebnerMatrix(38,67) = (groebnerMatrix(12,82)/(groebnerMatrix(12,70))-groebnerMatrix(31,78)/(groebnerMatrix(31,63))); groebnerMatrix(38,69) = -groebnerMatrix(31,80)/(groebnerMatrix(31,63)); groebnerMatrix(38,70) = -groebnerMatrix(31,81)/(groebnerMatrix(31,63)); groebnerMatrix(38,71) = -groebnerMatrix(31,82)/(groebnerMatrix(31,63)); groebnerMatrix(38,72) = groebnerMatrix(12,83)/(groebnerMatrix(12,70)); groebnerMatrix(38,76) = -groebnerMatrix(31,83)/(groebnerMatrix(31,63)); groebnerMatrix(38,78) = groebnerMatrix(12,84)/(groebnerMatrix(12,70)); groebnerMatrix(38,82) = -groebnerMatrix(31,84)/(groebnerMatrix(31,63)); } void opengv::absolute_pose::modules::gp3p::sPolynomial39( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(39,28) = -groebnerMatrix(32,67)/(groebnerMatrix(32,65)); groebnerMatrix(39,29) = -groebnerMatrix(32,68)/(groebnerMatrix(32,65)); groebnerMatrix(39,30) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(32,69)/(groebnerMatrix(32,65))); groebnerMatrix(39,33) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(39,42) = -groebnerMatrix(32,72)/(groebnerMatrix(32,65)); groebnerMatrix(39,43) = -groebnerMatrix(32,73)/(groebnerMatrix(32,65)); groebnerMatrix(39,44) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(32,74)/(groebnerMatrix(32,65))); groebnerMatrix(39,45) = -groebnerMatrix(32,75)/(groebnerMatrix(32,65)); groebnerMatrix(39,48) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(39,49) = -groebnerMatrix(32,76)/(groebnerMatrix(32,65)); groebnerMatrix(39,53) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(39,54) = -groebnerMatrix(32,77)/(groebnerMatrix(32,65)); groebnerMatrix(39,63) = -groebnerMatrix(32,78)/(groebnerMatrix(32,65)); groebnerMatrix(39,64) = -groebnerMatrix(32,79)/(groebnerMatrix(32,65)); groebnerMatrix(39,65) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(32,80)/(groebnerMatrix(32,65))); groebnerMatrix(39,66) = -groebnerMatrix(32,81)/(groebnerMatrix(32,65)); groebnerMatrix(39,69) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(39,70) = -groebnerMatrix(32,82)/(groebnerMatrix(32,65)); groebnerMatrix(39,74) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(39,75) = -groebnerMatrix(32,83)/(groebnerMatrix(32,65)); groebnerMatrix(39,80) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); groebnerMatrix(39,81) = -groebnerMatrix(32,84)/(groebnerMatrix(32,65)); } void opengv::absolute_pose::modules::gp3p::sPolynomial40( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(40,21) = -groebnerMatrix(30,65)/(groebnerMatrix(30,64)); groebnerMatrix(40,29) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(30,68)/(groebnerMatrix(30,64))); groebnerMatrix(40,30) = -groebnerMatrix(30,69)/(groebnerMatrix(30,64)); groebnerMatrix(40,32) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(40,43) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(30,73)/(groebnerMatrix(30,64))); groebnerMatrix(40,44) = -groebnerMatrix(30,74)/(groebnerMatrix(30,64)); groebnerMatrix(40,45) = -groebnerMatrix(30,75)/(groebnerMatrix(30,64)); groebnerMatrix(40,47) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(40,49) = -groebnerMatrix(30,76)/(groebnerMatrix(30,64)); groebnerMatrix(40,52) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(40,54) = -groebnerMatrix(30,77)/(groebnerMatrix(30,64)); groebnerMatrix(40,64) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(30,79)/(groebnerMatrix(30,64))); groebnerMatrix(40,65) = -groebnerMatrix(30,80)/(groebnerMatrix(30,64)); groebnerMatrix(40,66) = -groebnerMatrix(30,81)/(groebnerMatrix(30,64)); groebnerMatrix(40,68) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(40,70) = -groebnerMatrix(30,82)/(groebnerMatrix(30,64)); groebnerMatrix(40,73) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(40,75) = -groebnerMatrix(30,83)/(groebnerMatrix(30,64)); groebnerMatrix(40,79) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); groebnerMatrix(40,81) = -groebnerMatrix(30,84)/(groebnerMatrix(30,64)); } void opengv::absolute_pose::modules::gp3p::sPolynomial41( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(41,21) = -groebnerMatrix(31,65)/(groebnerMatrix(31,63)); groebnerMatrix(41,28) = (groebnerMatrix(10,70)/(groebnerMatrix(10,66))-groebnerMatrix(31,67)/(groebnerMatrix(31,63))); groebnerMatrix(41,30) = -groebnerMatrix(31,69)/(groebnerMatrix(31,63)); groebnerMatrix(41,31) = groebnerMatrix(10,71)/(groebnerMatrix(10,66)); groebnerMatrix(41,42) = (groebnerMatrix(10,75)/(groebnerMatrix(10,66))-groebnerMatrix(31,72)/(groebnerMatrix(31,63))); groebnerMatrix(41,44) = -groebnerMatrix(31,74)/(groebnerMatrix(31,63)); groebnerMatrix(41,45) = -groebnerMatrix(31,75)/(groebnerMatrix(31,63)); groebnerMatrix(41,46) = groebnerMatrix(10,76)/(groebnerMatrix(10,66)); groebnerMatrix(41,49) = -groebnerMatrix(31,76)/(groebnerMatrix(31,63)); groebnerMatrix(41,51) = groebnerMatrix(10,77)/(groebnerMatrix(10,66)); groebnerMatrix(41,54) = -groebnerMatrix(31,77)/(groebnerMatrix(31,63)); groebnerMatrix(41,63) = (groebnerMatrix(10,81)/(groebnerMatrix(10,66))-groebnerMatrix(31,78)/(groebnerMatrix(31,63))); groebnerMatrix(41,65) = -groebnerMatrix(31,80)/(groebnerMatrix(31,63)); groebnerMatrix(41,66) = -groebnerMatrix(31,81)/(groebnerMatrix(31,63)); groebnerMatrix(41,67) = groebnerMatrix(10,82)/(groebnerMatrix(10,66)); groebnerMatrix(41,70) = -groebnerMatrix(31,82)/(groebnerMatrix(31,63)); groebnerMatrix(41,72) = groebnerMatrix(10,83)/(groebnerMatrix(10,66)); groebnerMatrix(41,75) = -groebnerMatrix(31,83)/(groebnerMatrix(31,63)); groebnerMatrix(41,78) = groebnerMatrix(10,84)/(groebnerMatrix(10,66)); groebnerMatrix(41,81) = -groebnerMatrix(31,84)/(groebnerMatrix(31,63)); } void opengv::absolute_pose::modules::gp3p::sPolynomial42( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(42,18) = groebnerMatrix(30,65)/(groebnerMatrix(30,64)); groebnerMatrix(42,23) = -groebnerMatrix(32,67)/(groebnerMatrix(32,65)); groebnerMatrix(42,24) = -groebnerMatrix(32,68)/(groebnerMatrix(32,65)); groebnerMatrix(42,26) = (groebnerMatrix(30,68)/(groebnerMatrix(30,64))-groebnerMatrix(32,69)/(groebnerMatrix(32,65))); groebnerMatrix(42,27) = groebnerMatrix(30,69)/(groebnerMatrix(30,64)); groebnerMatrix(42,37) = -groebnerMatrix(32,72)/(groebnerMatrix(32,65)); groebnerMatrix(42,38) = -groebnerMatrix(32,73)/(groebnerMatrix(32,65)); groebnerMatrix(42,40) = (groebnerMatrix(30,73)/(groebnerMatrix(30,64))-groebnerMatrix(32,74)/(groebnerMatrix(32,65))); groebnerMatrix(42,41) = groebnerMatrix(30,74)/(groebnerMatrix(30,64)); groebnerMatrix(42,43) = -groebnerMatrix(32,75)/(groebnerMatrix(32,65)); groebnerMatrix(42,44) = groebnerMatrix(30,75)/(groebnerMatrix(30,64)); groebnerMatrix(42,47) = -groebnerMatrix(32,76)/(groebnerMatrix(32,65)); groebnerMatrix(42,48) = groebnerMatrix(30,76)/(groebnerMatrix(30,64)); groebnerMatrix(42,52) = -groebnerMatrix(32,77)/(groebnerMatrix(32,65)); groebnerMatrix(42,53) = groebnerMatrix(30,77)/(groebnerMatrix(30,64)); groebnerMatrix(42,58) = -groebnerMatrix(32,78)/(groebnerMatrix(32,65)); groebnerMatrix(42,59) = -groebnerMatrix(32,79)/(groebnerMatrix(32,65)); groebnerMatrix(42,61) = (groebnerMatrix(30,79)/(groebnerMatrix(30,64))-groebnerMatrix(32,80)/(groebnerMatrix(32,65))); groebnerMatrix(42,62) = groebnerMatrix(30,80)/(groebnerMatrix(30,64)); groebnerMatrix(42,64) = -groebnerMatrix(32,81)/(groebnerMatrix(32,65)); groebnerMatrix(42,65) = groebnerMatrix(30,81)/(groebnerMatrix(30,64)); groebnerMatrix(42,68) = -groebnerMatrix(32,82)/(groebnerMatrix(32,65)); groebnerMatrix(42,69) = groebnerMatrix(30,82)/(groebnerMatrix(30,64)); groebnerMatrix(42,73) = -groebnerMatrix(32,83)/(groebnerMatrix(32,65)); groebnerMatrix(42,74) = groebnerMatrix(30,83)/(groebnerMatrix(30,64)); groebnerMatrix(42,79) = -groebnerMatrix(32,84)/(groebnerMatrix(32,65)); groebnerMatrix(42,80) = groebnerMatrix(30,84)/(groebnerMatrix(30,64)); } void opengv::absolute_pose::modules::gp3p::sPolynomial43( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(43,18) = groebnerMatrix(31,65)/(groebnerMatrix(31,63)); groebnerMatrix(43,22) = -groebnerMatrix(32,67)/(groebnerMatrix(32,65)); groebnerMatrix(43,23) = -groebnerMatrix(32,68)/(groebnerMatrix(32,65)); groebnerMatrix(43,25) = (groebnerMatrix(31,67)/(groebnerMatrix(31,63))-groebnerMatrix(32,69)/(groebnerMatrix(32,65))); groebnerMatrix(43,27) = groebnerMatrix(31,69)/(groebnerMatrix(31,63)); groebnerMatrix(43,36) = -groebnerMatrix(32,72)/(groebnerMatrix(32,65)); groebnerMatrix(43,37) = -groebnerMatrix(32,73)/(groebnerMatrix(32,65)); groebnerMatrix(43,39) = (groebnerMatrix(31,72)/(groebnerMatrix(31,63))-groebnerMatrix(32,74)/(groebnerMatrix(32,65))); groebnerMatrix(43,41) = groebnerMatrix(31,74)/(groebnerMatrix(31,63)); groebnerMatrix(43,42) = -groebnerMatrix(32,75)/(groebnerMatrix(32,65)); groebnerMatrix(43,44) = groebnerMatrix(31,75)/(groebnerMatrix(31,63)); groebnerMatrix(43,46) = -groebnerMatrix(32,76)/(groebnerMatrix(32,65)); groebnerMatrix(43,48) = groebnerMatrix(31,76)/(groebnerMatrix(31,63)); groebnerMatrix(43,51) = -groebnerMatrix(32,77)/(groebnerMatrix(32,65)); groebnerMatrix(43,53) = groebnerMatrix(31,77)/(groebnerMatrix(31,63)); groebnerMatrix(43,57) = -groebnerMatrix(32,78)/(groebnerMatrix(32,65)); groebnerMatrix(43,58) = -groebnerMatrix(32,79)/(groebnerMatrix(32,65)); groebnerMatrix(43,60) = (groebnerMatrix(31,78)/(groebnerMatrix(31,63))-groebnerMatrix(32,80)/(groebnerMatrix(32,65))); groebnerMatrix(43,62) = groebnerMatrix(31,80)/(groebnerMatrix(31,63)); groebnerMatrix(43,63) = -groebnerMatrix(32,81)/(groebnerMatrix(32,65)); groebnerMatrix(43,65) = groebnerMatrix(31,81)/(groebnerMatrix(31,63)); groebnerMatrix(43,67) = -groebnerMatrix(32,82)/(groebnerMatrix(32,65)); groebnerMatrix(43,69) = groebnerMatrix(31,82)/(groebnerMatrix(31,63)); groebnerMatrix(43,72) = -groebnerMatrix(32,83)/(groebnerMatrix(32,65)); groebnerMatrix(43,74) = groebnerMatrix(31,83)/(groebnerMatrix(31,63)); groebnerMatrix(43,78) = -groebnerMatrix(32,84)/(groebnerMatrix(32,65)); groebnerMatrix(43,80) = groebnerMatrix(31,84)/(groebnerMatrix(31,63)); } void opengv::absolute_pose::modules::gp3p::sPolynomial44( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(44,16) = groebnerMatrix(30,65)/(groebnerMatrix(30,64)); groebnerMatrix(44,17) = -groebnerMatrix(31,65)/(groebnerMatrix(31,63)); groebnerMatrix(44,25) = groebnerMatrix(30,69)/(groebnerMatrix(30,64)); groebnerMatrix(44,26) = -groebnerMatrix(31,69)/(groebnerMatrix(31,63)); groebnerMatrix(44,39) = groebnerMatrix(30,74)/(groebnerMatrix(30,64)); groebnerMatrix(44,40) = -groebnerMatrix(31,74)/(groebnerMatrix(31,63)); groebnerMatrix(44,42) = groebnerMatrix(30,75)/(groebnerMatrix(30,64)); groebnerMatrix(44,43) = -groebnerMatrix(31,75)/(groebnerMatrix(31,63)); groebnerMatrix(44,46) = groebnerMatrix(30,76)/(groebnerMatrix(30,64)); groebnerMatrix(44,47) = -groebnerMatrix(31,76)/(groebnerMatrix(31,63)); groebnerMatrix(44,51) = groebnerMatrix(30,77)/(groebnerMatrix(30,64)); groebnerMatrix(44,52) = -groebnerMatrix(31,77)/(groebnerMatrix(31,63)); groebnerMatrix(44,60) = groebnerMatrix(30,80)/(groebnerMatrix(30,64)); groebnerMatrix(44,61) = -groebnerMatrix(31,80)/(groebnerMatrix(31,63)); groebnerMatrix(44,63) = groebnerMatrix(30,81)/(groebnerMatrix(30,64)); groebnerMatrix(44,64) = -groebnerMatrix(31,81)/(groebnerMatrix(31,63)); groebnerMatrix(44,67) = groebnerMatrix(30,82)/(groebnerMatrix(30,64)); groebnerMatrix(44,68) = -groebnerMatrix(31,82)/(groebnerMatrix(31,63)); groebnerMatrix(44,72) = groebnerMatrix(30,83)/(groebnerMatrix(30,64)); groebnerMatrix(44,73) = -groebnerMatrix(31,83)/(groebnerMatrix(31,63)); groebnerMatrix(44,78) = groebnerMatrix(30,84)/(groebnerMatrix(30,64)); groebnerMatrix(44,79) = -groebnerMatrix(31,84)/(groebnerMatrix(31,63)); } void opengv::absolute_pose::modules::gp3p::sPolynomial45( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(45,14) = groebnerMatrix(19,56)/(groebnerMatrix(19,55)); groebnerMatrix(45,15) = -groebnerMatrix(27,56)/(groebnerMatrix(27,53)); groebnerMatrix(45,30) = -groebnerMatrix(27,65)/(groebnerMatrix(27,53)); groebnerMatrix(45,33) = -groebnerMatrix(27,69)/(groebnerMatrix(27,53)); groebnerMatrix(45,44) = groebnerMatrix(19,75)/(groebnerMatrix(19,55)); groebnerMatrix(45,48) = (groebnerMatrix(19,76)/(groebnerMatrix(19,55))-groebnerMatrix(27,74)/(groebnerMatrix(27,53))); groebnerMatrix(45,49) = -groebnerMatrix(27,75)/(groebnerMatrix(27,53)); groebnerMatrix(45,50) = -groebnerMatrix(27,76)/(groebnerMatrix(27,53)); groebnerMatrix(45,53) = groebnerMatrix(19,77)/(groebnerMatrix(19,55)); groebnerMatrix(45,55) = -groebnerMatrix(27,77)/(groebnerMatrix(27,53)); groebnerMatrix(45,65) = groebnerMatrix(19,81)/(groebnerMatrix(19,55)); groebnerMatrix(45,69) = (groebnerMatrix(19,82)/(groebnerMatrix(19,55))-groebnerMatrix(27,80)/(groebnerMatrix(27,53))); groebnerMatrix(45,70) = -groebnerMatrix(27,81)/(groebnerMatrix(27,53)); groebnerMatrix(45,71) = -groebnerMatrix(27,82)/(groebnerMatrix(27,53)); groebnerMatrix(45,74) = groebnerMatrix(19,83)/(groebnerMatrix(19,55)); groebnerMatrix(45,76) = -groebnerMatrix(27,83)/(groebnerMatrix(27,53)); groebnerMatrix(45,80) = groebnerMatrix(19,84)/(groebnerMatrix(19,55)); groebnerMatrix(45,82) = -groebnerMatrix(27,84)/(groebnerMatrix(27,53)); } void opengv::absolute_pose::modules::gp3p::sPolynomial46( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(46,13) = groebnerMatrix(19,56)/(groebnerMatrix(19,55)); groebnerMatrix(46,15) = -groebnerMatrix(28,56)/(groebnerMatrix(28,52)); groebnerMatrix(46,29) = -groebnerMatrix(28,64)/(groebnerMatrix(28,52)); groebnerMatrix(46,32) = -groebnerMatrix(28,68)/(groebnerMatrix(28,52)); groebnerMatrix(46,43) = groebnerMatrix(19,75)/(groebnerMatrix(19,55)); groebnerMatrix(46,47) = (groebnerMatrix(19,76)/(groebnerMatrix(19,55))-groebnerMatrix(28,73)/(groebnerMatrix(28,52))); groebnerMatrix(46,49) = -groebnerMatrix(28,75)/(groebnerMatrix(28,52)); groebnerMatrix(46,50) = -groebnerMatrix(28,76)/(groebnerMatrix(28,52)); groebnerMatrix(46,52) = groebnerMatrix(19,77)/(groebnerMatrix(19,55)); groebnerMatrix(46,55) = -groebnerMatrix(28,77)/(groebnerMatrix(28,52)); groebnerMatrix(46,64) = groebnerMatrix(19,81)/(groebnerMatrix(19,55)); groebnerMatrix(46,68) = (groebnerMatrix(19,82)/(groebnerMatrix(19,55))-groebnerMatrix(28,79)/(groebnerMatrix(28,52))); groebnerMatrix(46,70) = -groebnerMatrix(28,81)/(groebnerMatrix(28,52)); groebnerMatrix(46,71) = -groebnerMatrix(28,82)/(groebnerMatrix(28,52)); groebnerMatrix(46,73) = groebnerMatrix(19,83)/(groebnerMatrix(19,55)); groebnerMatrix(46,76) = -groebnerMatrix(28,83)/(groebnerMatrix(28,52)); groebnerMatrix(46,79) = groebnerMatrix(19,84)/(groebnerMatrix(19,55)); groebnerMatrix(46,82) = -groebnerMatrix(28,84)/(groebnerMatrix(28,52)); } void opengv::absolute_pose::modules::gp3p::sPolynomial47( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(47,12) = groebnerMatrix(19,56)/(groebnerMatrix(19,55)); groebnerMatrix(47,15) = -groebnerMatrix(29,56)/(groebnerMatrix(29,51)); groebnerMatrix(47,28) = -groebnerMatrix(29,63)/(groebnerMatrix(29,51)); groebnerMatrix(47,31) = -groebnerMatrix(29,67)/(groebnerMatrix(29,51)); groebnerMatrix(47,42) = groebnerMatrix(19,75)/(groebnerMatrix(19,55)); groebnerMatrix(47,46) = (groebnerMatrix(19,76)/(groebnerMatrix(19,55))-groebnerMatrix(29,72)/(groebnerMatrix(29,51))); groebnerMatrix(47,49) = -groebnerMatrix(29,75)/(groebnerMatrix(29,51)); groebnerMatrix(47,50) = -groebnerMatrix(29,76)/(groebnerMatrix(29,51)); groebnerMatrix(47,51) = groebnerMatrix(19,77)/(groebnerMatrix(19,55)); groebnerMatrix(47,55) = -groebnerMatrix(29,77)/(groebnerMatrix(29,51)); groebnerMatrix(47,63) = groebnerMatrix(19,81)/(groebnerMatrix(19,55)); groebnerMatrix(47,67) = (groebnerMatrix(19,82)/(groebnerMatrix(19,55))-groebnerMatrix(29,78)/(groebnerMatrix(29,51))); groebnerMatrix(47,70) = -groebnerMatrix(29,81)/(groebnerMatrix(29,51)); groebnerMatrix(47,71) = -groebnerMatrix(29,82)/(groebnerMatrix(29,51)); groebnerMatrix(47,72) = groebnerMatrix(19,83)/(groebnerMatrix(19,55)); groebnerMatrix(47,76) = -groebnerMatrix(29,83)/(groebnerMatrix(29,51)); groebnerMatrix(47,78) = groebnerMatrix(19,84)/(groebnerMatrix(19,55)); groebnerMatrix(47,82) = -groebnerMatrix(29,84)/(groebnerMatrix(29,51)); } opengv/src/absolute_pose/modules/gp3p/init.cpp0000664016516101651610000002136013344612246020434 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gp3p::init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & f, const Eigen::Matrix & v, const Eigen::Matrix & p ) { groebnerMatrix(0,20) = -1*f(0,1); groebnerMatrix(0,21) = f(0,0); groebnerMatrix(0,32) = -1*f(0,1); groebnerMatrix(0,33) = f(0,0); groebnerMatrix(0,52) = -1*f(0,1); groebnerMatrix(0,53) = f(0,0); groebnerMatrix(0,66) = (((v(0,0)-v(0,1))+p(0,0))-p(0,1)); groebnerMatrix(0,71) = (((v(0,0)-v(0,1))+p(0,0))-p(0,1)); groebnerMatrix(0,75) = (-2*p(2,0)+2*p(2,1)); groebnerMatrix(0,76) = (-2*p(1,0)+2*p(1,1)); groebnerMatrix(0,77) = (((v(0,0)-v(0,1))-p(0,0))+p(0,1)); groebnerMatrix(0,79) = -1*f(0,1); groebnerMatrix(0,80) = f(0,0); groebnerMatrix(0,81) = (2*p(1,0)-2*p(1,1)); groebnerMatrix(0,82) = (-2*p(2,0)+2*p(2,1)); groebnerMatrix(0,84) = (((-p(0,0)+p(0,1))+v(0,0))-v(0,1)); groebnerMatrix(1,20) = -1*f(1,1); groebnerMatrix(1,21) = f(1,0); groebnerMatrix(1,32) = -1*f(1,1); groebnerMatrix(1,33) = f(1,0); groebnerMatrix(1,52) = -1*f(1,1); groebnerMatrix(1,53) = f(1,0); groebnerMatrix(1,66) = (((v(1,0)-v(1,1))+p(1,0))-p(1,1)); groebnerMatrix(1,70) = (-2*p(2,0)+2*p(2,1)); groebnerMatrix(1,71) = (((v(1,0)-v(1,1))-p(1,0))+p(1,1)); groebnerMatrix(1,76) = (2*p(0,1)-2*p(0,0)); groebnerMatrix(1,77) = (((v(1,0)-v(1,1))+p(1,0))-p(1,1)); groebnerMatrix(1,79) = -1*f(1,1); groebnerMatrix(1,80) = f(1,0); groebnerMatrix(1,81) = (-2*p(0,0)+2*p(0,1)); groebnerMatrix(1,83) = (2*p(2,0)-2*p(2,1)); groebnerMatrix(1,84) = (((-p(1,0)+p(1,1))+v(1,0))-v(1,1)); groebnerMatrix(2,20) = -1*f(2,1); groebnerMatrix(2,21) = f(2,0); groebnerMatrix(2,32) = -1*f(2,1); groebnerMatrix(2,33) = f(2,0); groebnerMatrix(2,52) = -1*f(2,1); groebnerMatrix(2,53) = f(2,0); groebnerMatrix(2,66) = (((v(2,0)-v(2,1))-p(2,0))+p(2,1)); groebnerMatrix(2,70) = (-2*p(1,0)+2*p(1,1)); groebnerMatrix(2,71) = (((v(2,0)-v(2,1))+p(2,0))-p(2,1)); groebnerMatrix(2,75) = (-2*p(0,0)+2*p(0,1)); groebnerMatrix(2,77) = (((v(2,0)-v(2,1))+p(2,0))-p(2,1)); groebnerMatrix(2,79) = -1*f(2,1); groebnerMatrix(2,80) = f(2,0); groebnerMatrix(2,82) = (2*p(0,0)-2*p(0,1)); groebnerMatrix(2,83) = (-2*p(1,0)+2*p(1,1)); groebnerMatrix(2,84) = (((-p(2,0)+p(2,1))+v(2,0))-v(2,1)); groebnerMatrix(3,19) = -1*f(0,2); groebnerMatrix(3,20) = f(0,1); groebnerMatrix(3,31) = -1*f(0,2); groebnerMatrix(3,32) = f(0,1); groebnerMatrix(3,51) = -1*f(0,2); groebnerMatrix(3,52) = f(0,1); groebnerMatrix(3,66) = (((v(0,1)+p(0,1))-v(0,2))-p(0,2)); groebnerMatrix(3,71) = (((v(0,1)+p(0,1))-v(0,2))-p(0,2)); groebnerMatrix(3,75) = (-2*p(2,1)+2*p(2,2)); groebnerMatrix(3,76) = (-2*p(1,1)+2*p(1,2)); groebnerMatrix(3,77) = (((v(0,1)-p(0,1))-v(0,2))+p(0,2)); groebnerMatrix(3,78) = -1*f(0,2); groebnerMatrix(3,79) = f(0,1); groebnerMatrix(3,81) = (2*p(1,1)-2*p(1,2)); groebnerMatrix(3,82) = (-2*p(2,1)+2*p(2,2)); groebnerMatrix(3,84) = (((-p(0,1)+p(0,2))-v(0,2))+v(0,1)); groebnerMatrix(4,19) = -1*f(1,2); groebnerMatrix(4,20) = f(1,1); groebnerMatrix(4,31) = -1*f(1,2); groebnerMatrix(4,32) = f(1,1); groebnerMatrix(4,51) = -1*f(1,2); groebnerMatrix(4,52) = f(1,1); groebnerMatrix(4,66) = (((v(1,1)+p(1,1))-v(1,2))-p(1,2)); groebnerMatrix(4,70) = (2*p(2,2)-2*p(2,1)); groebnerMatrix(4,71) = (((v(1,1)-p(1,1))-v(1,2))+p(1,2)); groebnerMatrix(4,76) = (-2*p(0,1)+2*p(0,2)); groebnerMatrix(4,77) = (((v(1,1)+p(1,1))-v(1,2))-p(1,2)); groebnerMatrix(4,78) = -1*f(1,2); groebnerMatrix(4,79) = f(1,1); groebnerMatrix(4,81) = (-2*p(0,1)+2*p(0,2)); groebnerMatrix(4,83) = (2*p(2,1)-2*p(2,2)); groebnerMatrix(4,84) = (((-p(1,1)+p(1,2))-v(1,2))+v(1,1)); groebnerMatrix(5,19) = -1*f(2,2); groebnerMatrix(5,20) = f(2,1); groebnerMatrix(5,31) = -1*f(2,2); groebnerMatrix(5,32) = f(2,1); groebnerMatrix(5,51) = -1*f(2,2); groebnerMatrix(5,52) = f(2,1); groebnerMatrix(5,66) = (((v(2,1)-p(2,1))-v(2,2))+p(2,2)); groebnerMatrix(5,70) = (-2*p(1,1)+2*p(1,2)); groebnerMatrix(5,71) = (((v(2,1)+p(2,1))-v(2,2))-p(2,2)); groebnerMatrix(5,75) = (-2*p(0,1)+2*p(0,2)); groebnerMatrix(5,77) = (((v(2,1)+p(2,1))-v(2,2))-p(2,2)); groebnerMatrix(5,78) = -1*f(2,2); groebnerMatrix(5,79) = f(2,1); groebnerMatrix(5,82) = (2*p(0,1)-2*p(0,2)); groebnerMatrix(5,83) = (-2*p(1,1)+2*p(1,2)); groebnerMatrix(5,84) = (((-p(2,1)+p(2,2))-v(2,2))+v(2,1)); groebnerMatrix(6,19) = f(0,2); groebnerMatrix(6,21) = -1*f(0,0); groebnerMatrix(6,31) = f(0,2); groebnerMatrix(6,33) = -1*f(0,0); groebnerMatrix(6,51) = f(0,2); groebnerMatrix(6,53) = -1*f(0,0); groebnerMatrix(6,66) = (((-v(0,0)-p(0,0))+v(0,2))+p(0,2)); groebnerMatrix(6,71) = (((-v(0,0)-p(0,0))+v(0,2))+p(0,2)); groebnerMatrix(6,75) = (2*p(2,0)-2*p(2,2)); groebnerMatrix(6,76) = (2*p(1,0)-2*p(1,2)); groebnerMatrix(6,77) = (((-v(0,0)+p(0,0))+v(0,2))-p(0,2)); groebnerMatrix(6,78) = f(0,2); groebnerMatrix(6,80) = -1*f(0,0); groebnerMatrix(6,81) = (-2*p(1,0)+2*p(1,2)); groebnerMatrix(6,82) = (2*p(2,0)-2*p(2,2)); groebnerMatrix(6,84) = (((p(0,0)-p(0,2))-v(0,0))+v(0,2)); groebnerMatrix(7,19) = f(1,2); groebnerMatrix(7,21) = -1*f(1,0); groebnerMatrix(7,31) = f(1,2); groebnerMatrix(7,33) = -1*f(1,0); groebnerMatrix(7,51) = f(1,2); groebnerMatrix(7,53) = -1*f(1,0); groebnerMatrix(7,66) = (((-v(1,0)-p(1,0))+v(1,2))+p(1,2)); groebnerMatrix(7,70) = (-2*p(2,2)+2*p(2,0)); groebnerMatrix(7,71) = (((-v(1,0)+p(1,0))+v(1,2))-p(1,2)); groebnerMatrix(7,76) = (2*p(0,0)-2*p(0,2)); groebnerMatrix(7,77) = (((-v(1,0)-p(1,0))+v(1,2))+p(1,2)); groebnerMatrix(7,78) = f(1,2); groebnerMatrix(7,80) = -1*f(1,0); groebnerMatrix(7,81) = (2*p(0,0)-2*p(0,2)); groebnerMatrix(7,83) = (-2*p(2,0)+2*p(2,2)); groebnerMatrix(7,84) = (((p(1,0)-p(1,2))-v(1,0))+v(1,2)); groebnerMatrix(8,19) = f(2,2); groebnerMatrix(8,21) = -1*f(2,0); groebnerMatrix(8,31) = f(2,2); groebnerMatrix(8,33) = -1*f(2,0); groebnerMatrix(8,51) = f(2,2); groebnerMatrix(8,53) = -1*f(2,0); groebnerMatrix(8,66) = (((-v(2,0)+p(2,0))+v(2,2))-p(2,2)); groebnerMatrix(8,70) = (2*p(1,0)-2*p(1,2)); groebnerMatrix(8,71) = (((-v(2,0)-p(2,0))+v(2,2))+p(2,2)); groebnerMatrix(8,75) = (2*p(0,0)-2*p(0,2)); groebnerMatrix(8,77) = (((-v(2,0)-p(2,0))+v(2,2))+p(2,2)); groebnerMatrix(8,78) = f(2,2); groebnerMatrix(8,80) = -1*f(2,0); groebnerMatrix(8,82) = (-2*p(0,0)+2*p(0,2)); groebnerMatrix(8,83) = (2*p(1,0)-2*p(1,2)); groebnerMatrix(8,84) = (((p(2,0)-p(2,2))-v(2,0))+v(2,2)); } opengv/src/absolute_pose/modules/gp3p/code.cpp0000664016516101651610000012216113344612246020404 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gp3p::compute( Eigen::Matrix & groebnerMatrix ) { double factor = 0.0; sPolynomial9(groebnerMatrix); sPolynomial10(groebnerMatrix); groebnerRow9_000000_f(groebnerMatrix,10); sPolynomial11(groebnerMatrix); groebnerRow10_000010_f(groebnerMatrix,11); groebnerRow10_000000_f(groebnerMatrix,11); sPolynomial12(groebnerMatrix); groebnerRow10_000010_f(groebnerMatrix,12); groebnerRow11_000000_f(groebnerMatrix,12); groebnerRow10_000000_f(groebnerMatrix,12); sPolynomial13(groebnerMatrix); groebnerRow10_000010_f(groebnerMatrix,13); groebnerRow10_000100_f(groebnerMatrix,13); groebnerRow12_000010_f(groebnerMatrix,13); groebnerRow12_000100_f(groebnerMatrix,13); groebnerRow10_000000_f(groebnerMatrix,13); groebnerRow12_000000_f(groebnerMatrix,13); sPolynomial14(groebnerMatrix); groebnerRow10_000100_f(groebnerMatrix,14); groebnerRow12_000100_f(groebnerMatrix,14); groebnerRow10_000000_f(groebnerMatrix,14); groebnerRow12_000000_f(groebnerMatrix,14); sPolynomial15(groebnerMatrix); groebnerRow10_000100_f(groebnerMatrix,15); groebnerRow12_000100_f(groebnerMatrix,15); groebnerRow14_000000_f(groebnerMatrix,15); groebnerRow10_000000_f(groebnerMatrix,15); groebnerRow12_000000_f(groebnerMatrix,15); sPolynomial16(groebnerMatrix); groebnerRow15_010000_f(groebnerMatrix,16); groebnerRow10_100000_f(groebnerMatrix,16); groebnerRow12_100000_f(groebnerMatrix,16); groebnerRow15_100000_f(groebnerMatrix,16); groebnerRow10_000000_f(groebnerMatrix,16); groebnerRow12_000000_f(groebnerMatrix,16); groebnerRow15_000000_f(groebnerMatrix,16); sPolynomial17(groebnerMatrix); groebnerRow15_000000_f(groebnerMatrix,17); sPolynomial18(groebnerMatrix); groebnerRow15_000100_f(groebnerMatrix,18); groebnerRow17_000000_f(groebnerMatrix,18); groebnerRow15_000000_f(groebnerMatrix,18); sPolynomial19(groebnerMatrix); groebnerRow12_010000_f(groebnerMatrix,19); groebnerRow15_010000_f(groebnerMatrix,19); groebnerRow10_100000_f(groebnerMatrix,19); groebnerRow12_100000_f(groebnerMatrix,19); groebnerRow15_100000_f(groebnerMatrix,19); groebnerRow16_000000_f(groebnerMatrix,19); groebnerRow10_000000_f(groebnerMatrix,19); groebnerRow12_000000_f(groebnerMatrix,19); groebnerRow15_000000_f(groebnerMatrix,19); sPolynomial20(groebnerMatrix); groebnerRow10_000100_f(groebnerMatrix,20); groebnerRow12_000001_f(groebnerMatrix,20); groebnerRow12_000100_f(groebnerMatrix,20); groebnerRow15_000001_f(groebnerMatrix,20); groebnerRow15_000100_f(groebnerMatrix,20); groebnerRow17_000000_f(groebnerMatrix,20); groebnerRow10_000000_f(groebnerMatrix,20); groebnerRow12_000000_f(groebnerMatrix,20); groebnerRow15_000000_f(groebnerMatrix,20); sPolynomial21(groebnerMatrix); groebnerRow19_000100_f(groebnerMatrix,21); groebnerRow17_000000_f(groebnerMatrix,21); groebnerRow16_000000_f(groebnerMatrix,21); groebnerRow19_000000_f(groebnerMatrix,21); sPolynomial22(groebnerMatrix); groebnerRow19_000010_f(groebnerMatrix,22); groebnerRow18_000000_f(groebnerMatrix,22); groebnerRow16_000000_f(groebnerMatrix,22); groebnerRow19_000000_f(groebnerMatrix,22); sPolynomial23(groebnerMatrix); groebnerRow19_000001_f(groebnerMatrix,23); groebnerRow20_000000_f(groebnerMatrix,23); groebnerRow16_000000_f(groebnerMatrix,23); groebnerRow19_000000_f(groebnerMatrix,23); sPolynomial24(groebnerMatrix); groebnerRow15_100100_f(groebnerMatrix,24); groebnerRow16_000100_f(groebnerMatrix,24); groebnerRow19_000100_f(groebnerMatrix,24); groebnerRow21_000000_f(groebnerMatrix,24); groebnerRow12_000100_f(groebnerMatrix,24); groebnerRow15_000100_f(groebnerMatrix,24); groebnerRow17_000000_f(groebnerMatrix,24); groebnerRow12_100000_f(groebnerMatrix,24); groebnerRow15_100000_f(groebnerMatrix,24); groebnerRow16_000000_f(groebnerMatrix,24); groebnerRow19_000000_f(groebnerMatrix,24); groebnerRow12_000000_f(groebnerMatrix,24); groebnerRow15_000000_f(groebnerMatrix,24); sPolynomial25(groebnerMatrix); groebnerRow15_100010_f(groebnerMatrix,25); groebnerRow16_000010_f(groebnerMatrix,25); groebnerRow19_000010_f(groebnerMatrix,25); groebnerRow22_000000_f(groebnerMatrix,25); groebnerRow12_000010_f(groebnerMatrix,25); groebnerRow15_000010_f(groebnerMatrix,25); groebnerRow18_000000_f(groebnerMatrix,25); groebnerRow12_100000_f(groebnerMatrix,25); groebnerRow15_100000_f(groebnerMatrix,25); groebnerRow16_000000_f(groebnerMatrix,25); groebnerRow19_000000_f(groebnerMatrix,25); groebnerRow12_000000_f(groebnerMatrix,25); groebnerRow15_000000_f(groebnerMatrix,25); sPolynomial26(groebnerMatrix); groebnerRow15_100001_f(groebnerMatrix,26); groebnerRow16_000001_f(groebnerMatrix,26); groebnerRow19_000001_f(groebnerMatrix,26); groebnerRow23_000000_f(groebnerMatrix,26); groebnerRow12_000001_f(groebnerMatrix,26); groebnerRow15_000001_f(groebnerMatrix,26); groebnerRow20_000000_f(groebnerMatrix,26); groebnerRow12_100000_f(groebnerMatrix,26); groebnerRow15_100000_f(groebnerMatrix,26); groebnerRow16_000000_f(groebnerMatrix,26); groebnerRow19_000000_f(groebnerMatrix,26); groebnerRow12_000000_f(groebnerMatrix,26); groebnerRow15_000000_f(groebnerMatrix,26); sPolynomial27(groebnerMatrix); groebnerRow12_100100_f(groebnerMatrix,27); groebnerRow15_100100_f(groebnerMatrix,27); groebnerRow16_000100_f(groebnerMatrix,27); groebnerRow19_000100_f(groebnerMatrix,27); groebnerRow21_000000_f(groebnerMatrix,27); groebnerRow10_000100_f(groebnerMatrix,27); groebnerRow12_000100_f(groebnerMatrix,27); groebnerRow15_000100_f(groebnerMatrix,27); groebnerRow17_000000_f(groebnerMatrix,27); groebnerRow10_100000_f(groebnerMatrix,27); groebnerRow24_000000_f(groebnerMatrix,27); groebnerRow12_100000_f(groebnerMatrix,27); groebnerRow15_100000_f(groebnerMatrix,27); groebnerRow16_000000_f(groebnerMatrix,27); groebnerRow19_000000_f(groebnerMatrix,27); groebnerRow10_000000_f(groebnerMatrix,27); groebnerRow12_000000_f(groebnerMatrix,27); groebnerRow15_000000_f(groebnerMatrix,27); sPolynomial28(groebnerMatrix); groebnerRow12_100010_f(groebnerMatrix,28); groebnerRow15_100010_f(groebnerMatrix,28); groebnerRow16_000010_f(groebnerMatrix,28); groebnerRow19_000010_f(groebnerMatrix,28); groebnerRow22_000000_f(groebnerMatrix,28); groebnerRow10_000010_f(groebnerMatrix,28); groebnerRow12_000010_f(groebnerMatrix,28); groebnerRow15_000010_f(groebnerMatrix,28); groebnerRow18_000000_f(groebnerMatrix,28); groebnerRow10_100000_f(groebnerMatrix,28); groebnerRow25_000000_f(groebnerMatrix,28); groebnerRow12_100000_f(groebnerMatrix,28); groebnerRow15_100000_f(groebnerMatrix,28); groebnerRow16_000000_f(groebnerMatrix,28); groebnerRow19_000000_f(groebnerMatrix,28); groebnerRow10_000000_f(groebnerMatrix,28); groebnerRow12_000000_f(groebnerMatrix,28); groebnerRow15_000000_f(groebnerMatrix,28); sPolynomial29(groebnerMatrix); groebnerRow12_100001_f(groebnerMatrix,29); groebnerRow15_100001_f(groebnerMatrix,29); groebnerRow16_000001_f(groebnerMatrix,29); groebnerRow19_000001_f(groebnerMatrix,29); groebnerRow23_000000_f(groebnerMatrix,29); groebnerRow10_000001_f(groebnerMatrix,29); groebnerRow12_000001_f(groebnerMatrix,29); groebnerRow15_000001_f(groebnerMatrix,29); groebnerRow20_000000_f(groebnerMatrix,29); groebnerRow10_100000_f(groebnerMatrix,29); groebnerRow26_000000_f(groebnerMatrix,29); groebnerRow12_100000_f(groebnerMatrix,29); groebnerRow15_100000_f(groebnerMatrix,29); groebnerRow16_000000_f(groebnerMatrix,29); groebnerRow19_000000_f(groebnerMatrix,29); groebnerRow10_000000_f(groebnerMatrix,29); groebnerRow12_000000_f(groebnerMatrix,29); groebnerRow15_000000_f(groebnerMatrix,29); sPolynomial30(groebnerMatrix); groebnerRow18_000000_f(groebnerMatrix,30); groebnerRow17_000000_f(groebnerMatrix,30); groebnerRow25_000000_f(groebnerMatrix,30); groebnerRow24_000000_f(groebnerMatrix,30); groebnerRow28_000000_f(groebnerMatrix,30); groebnerRow27_000000_f(groebnerMatrix,30); sPolynomial31(groebnerMatrix); groebnerRow20_000000_f(groebnerMatrix,31); groebnerRow17_000000_f(groebnerMatrix,31); groebnerRow26_000000_f(groebnerMatrix,31); groebnerRow24_000000_f(groebnerMatrix,31); groebnerRow29_000000_f(groebnerMatrix,31); groebnerRow27_000000_f(groebnerMatrix,31); sPolynomial32(groebnerMatrix); groebnerRow31_100000_f(groebnerMatrix,32); groebnerRow30_100000_f(groebnerMatrix,32); groebnerRow17_000000_f(groebnerMatrix,32); groebnerRow26_000000_f(groebnerMatrix,32); groebnerRow25_000000_f(groebnerMatrix,32); groebnerRow24_000000_f(groebnerMatrix,32); groebnerRow29_000000_f(groebnerMatrix,32); groebnerRow28_000000_f(groebnerMatrix,32); groebnerRow27_000000_f(groebnerMatrix,32); groebnerRow16_000000_f(groebnerMatrix,32); groebnerRow19_000000_f(groebnerMatrix,32); groebnerRow31_000000_f(groebnerMatrix,32); groebnerRow30_000000_f(groebnerMatrix,32); sPolynomial33(groebnerMatrix); groebnerRow26_000000_f(groebnerMatrix,33); groebnerRow25_000000_f(groebnerMatrix,33); groebnerRow24_000000_f(groebnerMatrix,33); groebnerRow29_000000_f(groebnerMatrix,33); groebnerRow28_000000_f(groebnerMatrix,33); groebnerRow27_000000_f(groebnerMatrix,33); groebnerRow16_000000_f(groebnerMatrix,33); groebnerRow19_000000_f(groebnerMatrix,33); groebnerRow31_000000_f(groebnerMatrix,33); groebnerRow30_000000_f(groebnerMatrix,33); groebnerRow32_000000_f(groebnerMatrix,33); sPolynomial34(groebnerMatrix); groebnerRow32_100000_f(groebnerMatrix,34); groebnerRow33_100000_f(groebnerMatrix,34); groebnerRow25_000000_f(groebnerMatrix,34); groebnerRow24_000000_f(groebnerMatrix,34); groebnerRow29_000000_f(groebnerMatrix,34); groebnerRow28_000000_f(groebnerMatrix,34); groebnerRow27_000000_f(groebnerMatrix,34); groebnerRow16_000000_f(groebnerMatrix,34); groebnerRow19_000000_f(groebnerMatrix,34); groebnerRow31_000000_f(groebnerMatrix,34); groebnerRow30_000000_f(groebnerMatrix,34); groebnerRow32_000000_f(groebnerMatrix,34); groebnerRow33_000000_f(groebnerMatrix,34); sPolynomial35(groebnerMatrix); groebnerRow32_100000_f(groebnerMatrix,35); groebnerRow33_100000_f(groebnerMatrix,35); groebnerRow34_100000_f(groebnerMatrix,35); groebnerRow24_000000_f(groebnerMatrix,35); groebnerRow29_000000_f(groebnerMatrix,35); groebnerRow28_000000_f(groebnerMatrix,35); groebnerRow27_000000_f(groebnerMatrix,35); groebnerRow16_000000_f(groebnerMatrix,35); groebnerRow19_000000_f(groebnerMatrix,35); groebnerRow31_000000_f(groebnerMatrix,35); groebnerRow30_000000_f(groebnerMatrix,35); groebnerRow32_000000_f(groebnerMatrix,35); groebnerRow33_000000_f(groebnerMatrix,35); groebnerRow34_000000_f(groebnerMatrix,35); sPolynomial36(groebnerMatrix); groebnerRow15_000001_f(groebnerMatrix,36); groebnerRow15_000010_f(groebnerMatrix,36); groebnerRow15_000100_f(groebnerMatrix,36); groebnerRow31_100000_f(groebnerMatrix,36); groebnerRow30_100000_f(groebnerMatrix,36); groebnerRow32_100000_f(groebnerMatrix,36); groebnerRow33_100000_f(groebnerMatrix,36); groebnerRow34_100000_f(groebnerMatrix,36); groebnerRow35_100000_f(groebnerMatrix,36); groebnerRow12_100000_f(groebnerMatrix,36); groebnerRow15_100000_f(groebnerMatrix,36); groebnerRow29_000000_f(groebnerMatrix,36); groebnerRow28_000000_f(groebnerMatrix,36); groebnerRow27_000000_f(groebnerMatrix,36); groebnerRow16_000000_f(groebnerMatrix,36); groebnerRow19_000000_f(groebnerMatrix,36); groebnerRow31_000000_f(groebnerMatrix,36); groebnerRow30_000000_f(groebnerMatrix,36); groebnerRow32_000000_f(groebnerMatrix,36); groebnerRow33_000000_f(groebnerMatrix,36); groebnerRow34_000000_f(groebnerMatrix,36); groebnerRow35_000000_f(groebnerMatrix,36); groebnerRow12_000000_f(groebnerMatrix,36); groebnerRow15_000000_f(groebnerMatrix,36); sPolynomial37(groebnerMatrix); groebnerRow12_000100_f(groebnerMatrix,37); groebnerRow15_000010_f(groebnerMatrix,37); groebnerRow15_000100_f(groebnerMatrix,37); groebnerRow30_100000_f(groebnerMatrix,37); groebnerRow32_100000_f(groebnerMatrix,37); groebnerRow33_100000_f(groebnerMatrix,37); groebnerRow34_100000_f(groebnerMatrix,37); groebnerRow35_100000_f(groebnerMatrix,37); groebnerRow12_100000_f(groebnerMatrix,37); groebnerRow15_100000_f(groebnerMatrix,37); groebnerRow29_000000_f(groebnerMatrix,37); groebnerRow28_000000_f(groebnerMatrix,37); groebnerRow27_000000_f(groebnerMatrix,37); groebnerRow16_000000_f(groebnerMatrix,37); groebnerRow19_000000_f(groebnerMatrix,37); groebnerRow31_000000_f(groebnerMatrix,37); groebnerRow30_000000_f(groebnerMatrix,37); groebnerRow32_000000_f(groebnerMatrix,37); groebnerRow33_000000_f(groebnerMatrix,37); groebnerRow34_000000_f(groebnerMatrix,37); groebnerRow35_000000_f(groebnerMatrix,37); groebnerRow12_000000_f(groebnerMatrix,37); groebnerRow15_000000_f(groebnerMatrix,37); sPolynomial38(groebnerMatrix); groebnerRow12_000100_f(groebnerMatrix,38); groebnerRow15_000001_f(groebnerMatrix,38); groebnerRow15_000100_f(groebnerMatrix,38); groebnerRow31_100000_f(groebnerMatrix,38); groebnerRow32_100000_f(groebnerMatrix,38); groebnerRow33_100000_f(groebnerMatrix,38); groebnerRow34_100000_f(groebnerMatrix,38); groebnerRow35_100000_f(groebnerMatrix,38); groebnerRow12_100000_f(groebnerMatrix,38); groebnerRow15_100000_f(groebnerMatrix,38); groebnerRow37_100000_f(groebnerMatrix,38); groebnerRow28_000000_f(groebnerMatrix,38); groebnerRow27_000000_f(groebnerMatrix,38); groebnerRow16_000000_f(groebnerMatrix,38); groebnerRow19_000000_f(groebnerMatrix,38); groebnerRow36_000000_f(groebnerMatrix,38); groebnerRow31_000000_f(groebnerMatrix,38); groebnerRow30_000000_f(groebnerMatrix,38); groebnerRow32_000000_f(groebnerMatrix,38); groebnerRow33_000000_f(groebnerMatrix,38); groebnerRow34_000000_f(groebnerMatrix,38); groebnerRow35_000000_f(groebnerMatrix,38); groebnerRow12_000000_f(groebnerMatrix,38); groebnerRow15_000000_f(groebnerMatrix,38); groebnerRow37_000000_f(groebnerMatrix,38); sPolynomial39(groebnerMatrix); groebnerRow12_000001_f(groebnerMatrix,39); groebnerRow12_000010_f(groebnerMatrix,39); groebnerRow12_000100_f(groebnerMatrix,39); groebnerRow15_000001_f(groebnerMatrix,39); groebnerRow15_000010_f(groebnerMatrix,39); groebnerRow15_000100_f(groebnerMatrix,39); groebnerRow31_100000_f(groebnerMatrix,39); groebnerRow30_100000_f(groebnerMatrix,39); groebnerRow32_100000_f(groebnerMatrix,39); groebnerRow10_100000_f(groebnerMatrix,39); groebnerRow33_100000_f(groebnerMatrix,39); groebnerRow34_100000_f(groebnerMatrix,39); groebnerRow35_100000_f(groebnerMatrix,39); groebnerRow12_100000_f(groebnerMatrix,39); groebnerRow15_100000_f(groebnerMatrix,39); groebnerRow37_100000_f(groebnerMatrix,39); groebnerRow38_100000_f(groebnerMatrix,39); groebnerRow27_000000_f(groebnerMatrix,39); groebnerRow16_000000_f(groebnerMatrix,39); groebnerRow19_000000_f(groebnerMatrix,39); groebnerRow36_000000_f(groebnerMatrix,39); groebnerRow31_000000_f(groebnerMatrix,39); groebnerRow30_000000_f(groebnerMatrix,39); groebnerRow32_000000_f(groebnerMatrix,39); groebnerRow10_000000_f(groebnerMatrix,39); groebnerRow33_000000_f(groebnerMatrix,39); groebnerRow34_000000_f(groebnerMatrix,39); groebnerRow35_000000_f(groebnerMatrix,39); groebnerRow12_000000_f(groebnerMatrix,39); groebnerRow15_000000_f(groebnerMatrix,39); groebnerRow37_000000_f(groebnerMatrix,39); groebnerRow38_000000_f(groebnerMatrix,39); sPolynomial40(groebnerMatrix); groebnerRow10_000100_f(groebnerMatrix,40); groebnerRow12_000010_f(groebnerMatrix,40); groebnerRow12_000100_f(groebnerMatrix,40); groebnerRow15_000010_f(groebnerMatrix,40); groebnerRow15_000100_f(groebnerMatrix,40); groebnerRow30_100000_f(groebnerMatrix,40); groebnerRow32_100000_f(groebnerMatrix,40); groebnerRow10_100000_f(groebnerMatrix,40); groebnerRow33_100000_f(groebnerMatrix,40); groebnerRow34_100000_f(groebnerMatrix,40); groebnerRow35_100000_f(groebnerMatrix,40); groebnerRow12_100000_f(groebnerMatrix,40); groebnerRow15_100000_f(groebnerMatrix,40); groebnerRow37_100000_f(groebnerMatrix,40); groebnerRow38_100000_f(groebnerMatrix,40); groebnerRow39_100000_f(groebnerMatrix,40); groebnerRow16_000000_f(groebnerMatrix,40); groebnerRow19_000000_f(groebnerMatrix,40); groebnerRow36_000000_f(groebnerMatrix,40); groebnerRow30_000000_f(groebnerMatrix,40); groebnerRow32_000000_f(groebnerMatrix,40); groebnerRow10_000000_f(groebnerMatrix,40); groebnerRow33_000000_f(groebnerMatrix,40); groebnerRow34_000000_f(groebnerMatrix,40); groebnerRow35_000000_f(groebnerMatrix,40); groebnerRow12_000000_f(groebnerMatrix,40); groebnerRow15_000000_f(groebnerMatrix,40); groebnerRow37_000000_f(groebnerMatrix,40); groebnerRow38_000000_f(groebnerMatrix,40); groebnerRow39_000000_f(groebnerMatrix,40); sPolynomial41(groebnerMatrix); groebnerRow10_000100_f(groebnerMatrix,41); groebnerRow12_000001_f(groebnerMatrix,41); groebnerRow12_000100_f(groebnerMatrix,41); groebnerRow15_000001_f(groebnerMatrix,41); groebnerRow15_000100_f(groebnerMatrix,41); groebnerRow31_100000_f(groebnerMatrix,41); groebnerRow32_100000_f(groebnerMatrix,41); groebnerRow10_100000_f(groebnerMatrix,41); groebnerRow33_100000_f(groebnerMatrix,41); groebnerRow34_100000_f(groebnerMatrix,41); groebnerRow35_100000_f(groebnerMatrix,41); groebnerRow12_100000_f(groebnerMatrix,41); groebnerRow15_100000_f(groebnerMatrix,41); groebnerRow37_100000_f(groebnerMatrix,41); groebnerRow38_100000_f(groebnerMatrix,41); groebnerRow39_100000_f(groebnerMatrix,41); groebnerRow40_100000_f(groebnerMatrix,41); groebnerRow19_000000_f(groebnerMatrix,41); groebnerRow36_000000_f(groebnerMatrix,41); groebnerRow31_000000_f(groebnerMatrix,41); groebnerRow32_000000_f(groebnerMatrix,41); groebnerRow10_000000_f(groebnerMatrix,41); groebnerRow33_000000_f(groebnerMatrix,41); groebnerRow34_000000_f(groebnerMatrix,41); groebnerRow35_000000_f(groebnerMatrix,41); groebnerRow12_000000_f(groebnerMatrix,41); groebnerRow15_000000_f(groebnerMatrix,41); groebnerRow37_000000_f(groebnerMatrix,41); groebnerRow38_000000_f(groebnerMatrix,41); groebnerRow39_000000_f(groebnerMatrix,41); groebnerRow40_000000_f(groebnerMatrix,41); sPolynomial42(groebnerMatrix); groebnerRow32_000100_f(groebnerMatrix,42); groebnerRow33_000010_f(groebnerMatrix,42); groebnerRow34_000010_f(groebnerMatrix,42); groebnerRow33_000100_f(groebnerMatrix,42); groebnerRow34_000100_f(groebnerMatrix,42); groebnerRow35_000100_f(groebnerMatrix,42); groebnerRow37_000010_f(groebnerMatrix,42); groebnerRow38_000010_f(groebnerMatrix,42); groebnerRow37_000100_f(groebnerMatrix,42); groebnerRow38_000100_f(groebnerMatrix,42); groebnerRow39_000100_f(groebnerMatrix,42); groebnerRow30_100000_f(groebnerMatrix,42); groebnerRow32_100000_f(groebnerMatrix,42); groebnerRow33_100000_f(groebnerMatrix,42); groebnerRow34_100000_f(groebnerMatrix,42); groebnerRow35_100000_f(groebnerMatrix,42); groebnerRow37_100000_f(groebnerMatrix,42); groebnerRow38_100000_f(groebnerMatrix,42); groebnerRow39_100000_f(groebnerMatrix,42); groebnerRow40_100000_f(groebnerMatrix,42); groebnerRow41_100000_f(groebnerMatrix,42); groebnerRow36_000000_f(groebnerMatrix,42); groebnerRow30_000000_f(groebnerMatrix,42); groebnerRow32_000000_f(groebnerMatrix,42); groebnerRow33_000000_f(groebnerMatrix,42); groebnerRow34_000000_f(groebnerMatrix,42); groebnerRow35_000000_f(groebnerMatrix,42); groebnerRow37_000000_f(groebnerMatrix,42); groebnerRow38_000000_f(groebnerMatrix,42); groebnerRow39_000000_f(groebnerMatrix,42); groebnerRow40_000000_f(groebnerMatrix,42); groebnerRow41_000000_f(groebnerMatrix,42); sPolynomial43(groebnerMatrix); groebnerRow32_000100_f(groebnerMatrix,43); groebnerRow33_000001_f(groebnerMatrix,43); groebnerRow33_000010_f(groebnerMatrix,43); groebnerRow34_000010_f(groebnerMatrix,43); groebnerRow33_000100_f(groebnerMatrix,43); groebnerRow34_000100_f(groebnerMatrix,43); groebnerRow35_000100_f(groebnerMatrix,43); groebnerRow37_000001_f(groebnerMatrix,43); groebnerRow37_000010_f(groebnerMatrix,43); groebnerRow38_000010_f(groebnerMatrix,43); groebnerRow37_000100_f(groebnerMatrix,43); groebnerRow38_000100_f(groebnerMatrix,43); groebnerRow39_000100_f(groebnerMatrix,43); groebnerRow31_100000_f(groebnerMatrix,43); groebnerRow30_100000_f(groebnerMatrix,43); groebnerRow32_100000_f(groebnerMatrix,43); groebnerRow33_100000_f(groebnerMatrix,43); groebnerRow34_100000_f(groebnerMatrix,43); groebnerRow35_100000_f(groebnerMatrix,43); groebnerRow37_100000_f(groebnerMatrix,43); groebnerRow38_100000_f(groebnerMatrix,43); groebnerRow39_100000_f(groebnerMatrix,43); groebnerRow40_100000_f(groebnerMatrix,43); groebnerRow41_100000_f(groebnerMatrix,43); groebnerRow36_000000_f(groebnerMatrix,43); groebnerRow42_000000_f(groebnerMatrix,43); groebnerRow31_000000_f(groebnerMatrix,43); groebnerRow30_000000_f(groebnerMatrix,43); groebnerRow32_000000_f(groebnerMatrix,43); groebnerRow33_000000_f(groebnerMatrix,43); groebnerRow34_000000_f(groebnerMatrix,43); groebnerRow35_000000_f(groebnerMatrix,43); groebnerRow37_000000_f(groebnerMatrix,43); groebnerRow38_000000_f(groebnerMatrix,43); groebnerRow39_000000_f(groebnerMatrix,43); groebnerRow40_000000_f(groebnerMatrix,43); groebnerRow41_000000_f(groebnerMatrix,43); sPolynomial44(groebnerMatrix); groebnerRow31_000100_f(groebnerMatrix,44); groebnerRow30_000100_f(groebnerMatrix,44); groebnerRow33_000100_f(groebnerMatrix,44); groebnerRow34_000100_f(groebnerMatrix,44); groebnerRow35_000100_f(groebnerMatrix,44); groebnerRow37_000100_f(groebnerMatrix,44); groebnerRow38_000100_f(groebnerMatrix,44); groebnerRow39_000100_f(groebnerMatrix,44); groebnerRow31_100000_f(groebnerMatrix,44); groebnerRow30_100000_f(groebnerMatrix,44); groebnerRow32_100000_f(groebnerMatrix,44); groebnerRow33_100000_f(groebnerMatrix,44); groebnerRow34_100000_f(groebnerMatrix,44); groebnerRow35_100000_f(groebnerMatrix,44); groebnerRow37_100000_f(groebnerMatrix,44); groebnerRow38_100000_f(groebnerMatrix,44); groebnerRow39_100000_f(groebnerMatrix,44); groebnerRow40_100000_f(groebnerMatrix,44); groebnerRow41_100000_f(groebnerMatrix,44); groebnerRow36_000000_f(groebnerMatrix,44); groebnerRow31_000000_f(groebnerMatrix,44); groebnerRow30_000000_f(groebnerMatrix,44); groebnerRow32_000000_f(groebnerMatrix,44); groebnerRow33_000000_f(groebnerMatrix,44); groebnerRow34_000000_f(groebnerMatrix,44); groebnerRow35_000000_f(groebnerMatrix,44); groebnerRow37_000000_f(groebnerMatrix,44); groebnerRow38_000000_f(groebnerMatrix,44); groebnerRow39_000000_f(groebnerMatrix,44); groebnerRow40_000000_f(groebnerMatrix,44); groebnerRow41_000000_f(groebnerMatrix,44); sPolynomial45(groebnerMatrix); groebnerRow36_000100_f(groebnerMatrix,45); groebnerRow36_010000_f(groebnerMatrix,45); groebnerRow12_000100_f(groebnerMatrix,45); groebnerRow15_000100_f(groebnerMatrix,45); groebnerRow37_000100_f(groebnerMatrix,45); groebnerRow38_000100_f(groebnerMatrix,45); groebnerRow39_000100_f(groebnerMatrix,45); groebnerRow32_100000_f(groebnerMatrix,45); groebnerRow33_100000_f(groebnerMatrix,45); groebnerRow34_100000_f(groebnerMatrix,45); groebnerRow35_100000_f(groebnerMatrix,45); groebnerRow12_100000_f(groebnerMatrix,45); groebnerRow15_100000_f(groebnerMatrix,45); groebnerRow37_100000_f(groebnerMatrix,45); groebnerRow38_100000_f(groebnerMatrix,45); groebnerRow39_100000_f(groebnerMatrix,45); groebnerRow40_100000_f(groebnerMatrix,45); groebnerRow41_100000_f(groebnerMatrix,45); groebnerRow36_000000_f(groebnerMatrix,45); groebnerRow44_000000_f(groebnerMatrix,45); groebnerRow32_000000_f(groebnerMatrix,45); groebnerRow33_000000_f(groebnerMatrix,45); groebnerRow34_000000_f(groebnerMatrix,45); groebnerRow35_000000_f(groebnerMatrix,45); groebnerRow12_000000_f(groebnerMatrix,45); groebnerRow15_000000_f(groebnerMatrix,45); groebnerRow37_000000_f(groebnerMatrix,45); groebnerRow38_000000_f(groebnerMatrix,45); groebnerRow39_000000_f(groebnerMatrix,45); groebnerRow40_000000_f(groebnerMatrix,45); groebnerRow41_000000_f(groebnerMatrix,45); sPolynomial46(groebnerMatrix); groebnerRow36_000010_f(groebnerMatrix,46); groebnerRow36_010000_f(groebnerMatrix,46); groebnerRow12_000010_f(groebnerMatrix,46); groebnerRow15_000010_f(groebnerMatrix,46); groebnerRow37_000010_f(groebnerMatrix,46); groebnerRow38_000010_f(groebnerMatrix,46); groebnerRow38_000100_f(groebnerMatrix,46); groebnerRow39_000100_f(groebnerMatrix,46); groebnerRow30_100000_f(groebnerMatrix,46); groebnerRow32_100000_f(groebnerMatrix,46); groebnerRow33_100000_f(groebnerMatrix,46); groebnerRow34_100000_f(groebnerMatrix,46); groebnerRow35_100000_f(groebnerMatrix,46); groebnerRow12_100000_f(groebnerMatrix,46); groebnerRow15_100000_f(groebnerMatrix,46); groebnerRow37_100000_f(groebnerMatrix,46); groebnerRow38_100000_f(groebnerMatrix,46); groebnerRow39_100000_f(groebnerMatrix,46); groebnerRow40_100000_f(groebnerMatrix,46); groebnerRow41_100000_f(groebnerMatrix,46); groebnerRow36_000000_f(groebnerMatrix,46); groebnerRow42_000000_f(groebnerMatrix,46); groebnerRow44_000000_f(groebnerMatrix,46); groebnerRow45_000000_f(groebnerMatrix,46); groebnerRow30_000000_f(groebnerMatrix,46); groebnerRow32_000000_f(groebnerMatrix,46); groebnerRow33_000000_f(groebnerMatrix,46); groebnerRow34_000000_f(groebnerMatrix,46); groebnerRow35_000000_f(groebnerMatrix,46); groebnerRow12_000000_f(groebnerMatrix,46); groebnerRow15_000000_f(groebnerMatrix,46); groebnerRow37_000000_f(groebnerMatrix,46); groebnerRow38_000000_f(groebnerMatrix,46); groebnerRow39_000000_f(groebnerMatrix,46); groebnerRow40_000000_f(groebnerMatrix,46); groebnerRow41_000000_f(groebnerMatrix,46); sPolynomial47(groebnerMatrix); groebnerRow36_000001_f(groebnerMatrix,47); groebnerRow36_010000_f(groebnerMatrix,47); groebnerRow12_000001_f(groebnerMatrix,47); groebnerRow15_000001_f(groebnerMatrix,47); groebnerRow37_000001_f(groebnerMatrix,47); groebnerRow37_000010_f(groebnerMatrix,47); groebnerRow38_000010_f(groebnerMatrix,47); groebnerRow37_000100_f(groebnerMatrix,47); groebnerRow38_000100_f(groebnerMatrix,47); groebnerRow39_000100_f(groebnerMatrix,47); groebnerRow31_100000_f(groebnerMatrix,47); groebnerRow30_100000_f(groebnerMatrix,47); groebnerRow32_100000_f(groebnerMatrix,47); groebnerRow33_100000_f(groebnerMatrix,47); groebnerRow34_100000_f(groebnerMatrix,47); groebnerRow35_100000_f(groebnerMatrix,47); groebnerRow12_100000_f(groebnerMatrix,47); groebnerRow15_100000_f(groebnerMatrix,47); groebnerRow37_100000_f(groebnerMatrix,47); groebnerRow38_100000_f(groebnerMatrix,47); groebnerRow39_100000_f(groebnerMatrix,47); groebnerRow40_100000_f(groebnerMatrix,47); groebnerRow41_100000_f(groebnerMatrix,47); groebnerRow36_000000_f(groebnerMatrix,47); groebnerRow43_000000_f(groebnerMatrix,47); groebnerRow42_000000_f(groebnerMatrix,47); groebnerRow46_000000_f(groebnerMatrix,47); groebnerRow44_000000_f(groebnerMatrix,47); groebnerRow45_000000_f(groebnerMatrix,47); groebnerRow31_000000_f(groebnerMatrix,47); groebnerRow30_000000_f(groebnerMatrix,47); groebnerRow32_000000_f(groebnerMatrix,47); groebnerRow33_000000_f(groebnerMatrix,47); groebnerRow34_000000_f(groebnerMatrix,47); groebnerRow35_000000_f(groebnerMatrix,47); groebnerRow12_000000_f(groebnerMatrix,47); groebnerRow15_000000_f(groebnerMatrix,47); groebnerRow37_000000_f(groebnerMatrix,47); groebnerRow38_000000_f(groebnerMatrix,47); groebnerRow39_000000_f(groebnerMatrix,47); groebnerRow40_000000_f(groebnerMatrix,47); groebnerRow41_000000_f(groebnerMatrix,47); factor = 1.0 / groebnerMatrix(10,66); groebnerMatrix.row(10) = factor * groebnerMatrix.row(10); factor = 1.0 / groebnerMatrix(12,70); groebnerMatrix.row(12) = factor * groebnerMatrix.row(12); factor = 1.0 / groebnerMatrix(15,71); groebnerMatrix.row(15) = factor * groebnerMatrix.row(15); factor = 1.0 / groebnerMatrix(30,64); groebnerMatrix.row(30) = factor * groebnerMatrix.row(30); factor = 1.0 / groebnerMatrix(31,63); groebnerMatrix.row(31) = factor * groebnerMatrix.row(31); factor = 1.0 / groebnerMatrix(32,65); groebnerMatrix.row(32) = factor * groebnerMatrix.row(32); factor = 1.0 / groebnerMatrix(33,67); groebnerMatrix.row(33) = factor * groebnerMatrix.row(33); factor = 1.0 / groebnerMatrix(34,68); groebnerMatrix.row(34) = factor * groebnerMatrix.row(34); factor = 1.0 / groebnerMatrix(35,69); groebnerMatrix.row(35) = factor * groebnerMatrix.row(35); factor = 1.0 / groebnerMatrix(36,56); groebnerMatrix.row(36) = factor * groebnerMatrix.row(36); factor = 1.0 / groebnerMatrix(37,72); groebnerMatrix.row(37) = factor * groebnerMatrix.row(37); factor = 1.0 / groebnerMatrix(38,73); groebnerMatrix.row(38) = factor * groebnerMatrix.row(38); factor = 1.0 / groebnerMatrix(39,74); groebnerMatrix.row(39) = factor * groebnerMatrix.row(39); factor = 1.0 / groebnerMatrix(40,75); groebnerMatrix.row(40) = factor * groebnerMatrix.row(40); factor = 1.0 / groebnerMatrix(41,76); groebnerMatrix.row(41) = factor * groebnerMatrix.row(41); factor = 1.0 / groebnerMatrix(42,58); groebnerMatrix.row(42) = factor * groebnerMatrix.row(42); factor = 1.0 / groebnerMatrix(43,57); groebnerMatrix.row(43) = factor * groebnerMatrix.row(43); factor = 1.0 / groebnerMatrix(44,60); groebnerMatrix.row(44) = factor * groebnerMatrix.row(44); factor = 1.0 / groebnerMatrix(45,61); groebnerMatrix.row(45) = factor * groebnerMatrix.row(45); factor = 1.0 / groebnerMatrix(46,59); groebnerMatrix.row(46) = factor * groebnerMatrix.row(46); factor = 1.0 / groebnerMatrix(47,62); groebnerMatrix.row(47) = factor * groebnerMatrix.row(47); factor = groebnerMatrix(10,70); groebnerMatrix.row(10) = groebnerMatrix.row(10) - factor * groebnerMatrix.row(12); factor = groebnerMatrix(10,71); groebnerMatrix.row(10) = groebnerMatrix.row(10) - factor * groebnerMatrix.row(15); factor = groebnerMatrix(10,75); groebnerMatrix.row(10) = groebnerMatrix.row(10) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(10,76); groebnerMatrix.row(10) = groebnerMatrix.row(10) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(12,71); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(15); factor = groebnerMatrix(12,75); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(12,76); groebnerMatrix.row(12) = groebnerMatrix.row(12) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(15,75); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(15,76); groebnerMatrix.row(15) = groebnerMatrix.row(15) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(30,65); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(30,67); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(30,68); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(30,69); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(30,72); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(30,73); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(30,74); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(30,75); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(30,76); groebnerMatrix.row(30) = groebnerMatrix.row(30) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(31,65); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(32); factor = groebnerMatrix(31,67); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(31,68); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(31,69); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(31,72); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(31,73); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(31,74); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(31,75); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(31,76); groebnerMatrix.row(31) = groebnerMatrix.row(31) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(32,67); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(33); factor = groebnerMatrix(32,68); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(32,69); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(32,72); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(32,73); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(32,74); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(32,75); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(32,76); groebnerMatrix.row(32) = groebnerMatrix.row(32) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(33,68); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(34); factor = groebnerMatrix(33,69); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(33,72); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(33,73); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(33,74); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(33,75); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(33,76); groebnerMatrix.row(33) = groebnerMatrix.row(33) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(34,69); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(35); factor = groebnerMatrix(34,72); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(34,73); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(34,74); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(34,75); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(34,76); groebnerMatrix.row(34) = groebnerMatrix.row(34) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(35,72); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(35,73); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(35,74); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(35,75); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(35,76); groebnerMatrix.row(35) = groebnerMatrix.row(35) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(36,72); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(37); factor = groebnerMatrix(36,73); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(36,74); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(36,75); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(36,76); groebnerMatrix.row(36) = groebnerMatrix.row(36) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(37,73); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(38); factor = groebnerMatrix(37,74); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(37,75); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(37,76); groebnerMatrix.row(37) = groebnerMatrix.row(37) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(38,74); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(39); factor = groebnerMatrix(38,75); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(38,76); groebnerMatrix.row(38) = groebnerMatrix.row(38) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(39,75); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(40); factor = groebnerMatrix(39,76); groebnerMatrix.row(39) = groebnerMatrix.row(39) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(40,76); groebnerMatrix.row(40) = groebnerMatrix.row(40) - factor * groebnerMatrix.row(41); factor = groebnerMatrix(42,59); groebnerMatrix.row(42) = groebnerMatrix.row(42) - factor * groebnerMatrix.row(46); factor = groebnerMatrix(42,60); groebnerMatrix.row(42) = groebnerMatrix.row(42) - factor * groebnerMatrix.row(44); factor = groebnerMatrix(42,61); groebnerMatrix.row(42) = groebnerMatrix.row(42) - factor * groebnerMatrix.row(45); factor = groebnerMatrix(42,62); groebnerMatrix.row(42) = groebnerMatrix.row(42) - factor * groebnerMatrix.row(47); factor = groebnerMatrix(43,59); groebnerMatrix.row(43) = groebnerMatrix.row(43) - factor * groebnerMatrix.row(46); factor = groebnerMatrix(43,60); groebnerMatrix.row(43) = groebnerMatrix.row(43) - factor * groebnerMatrix.row(44); factor = groebnerMatrix(43,61); groebnerMatrix.row(43) = groebnerMatrix.row(43) - factor * groebnerMatrix.row(45); factor = groebnerMatrix(43,62); groebnerMatrix.row(43) = groebnerMatrix.row(43) - factor * groebnerMatrix.row(47); factor = groebnerMatrix(44,61); groebnerMatrix.row(44) = groebnerMatrix.row(44) - factor * groebnerMatrix.row(45); factor = groebnerMatrix(44,62); groebnerMatrix.row(44) = groebnerMatrix.row(44) - factor * groebnerMatrix.row(47); factor = groebnerMatrix(45,62); groebnerMatrix.row(45) = groebnerMatrix.row(45) - factor * groebnerMatrix.row(47); factor = groebnerMatrix(46,62); groebnerMatrix.row(46) = groebnerMatrix.row(46) - factor * groebnerMatrix.row(47); } opengv/src/absolute_pose/modules/Epnp.cpp0000664016516101651610000005732713344612246017536 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ // Note: this code has been downloaded from the homepage of the "Computer // Vision Laboratory" at EPFL Lausanne, and was originally developped by the // authors of [4]. I only adapted it to Eigen. #include using namespace std; #include opengv::absolute_pose::modules::Epnp::Epnp(void) { maximum_number_of_correspondences = 0; number_of_correspondences = 0; pws = 0; us = 0; alphas = 0; pcs = 0; signs = 0; //added this->uc = 0.0; this->vc = 0.0; this->fu = 1.0; this->fv = 1.0; } opengv::absolute_pose::modules::Epnp::~Epnp() { delete [] pws; delete [] us; delete [] alphas; delete [] pcs; delete [] signs; //added } void opengv::absolute_pose::modules::Epnp:: set_maximum_number_of_correspondences(int n) { if (maximum_number_of_correspondences < n) { if (pws != 0) delete [] pws; if (us != 0) delete [] us; if (alphas != 0) delete [] alphas; if (pcs != 0) delete [] pcs; if (signs != 0) delete [] signs; //added maximum_number_of_correspondences = n; pws = new double[3 * maximum_number_of_correspondences]; us = new double[2 * maximum_number_of_correspondences]; alphas = new double[4 * maximum_number_of_correspondences]; pcs = new double[3 * maximum_number_of_correspondences]; signs = new int[maximum_number_of_correspondences]; } } void opengv::absolute_pose::modules::Epnp::reset_correspondences(void) { number_of_correspondences = 0; } void opengv::absolute_pose::modules::Epnp::add_correspondence( double X, double Y, double Z, double x, double y, double z) //changed this interface { pws[3 * number_of_correspondences ] = X; pws[3 * number_of_correspondences + 1] = Y; pws[3 * number_of_correspondences + 2] = Z; us[2 * number_of_correspondences ] = x/z; us[2 * number_of_correspondences + 1] = y/z; //added the following if(z > 0.0) signs[number_of_correspondences] = 1; else signs[number_of_correspondences] = -1; number_of_correspondences++; } void opengv::absolute_pose::modules::Epnp::choose_control_points(void) { // Take C0 as the reference points centroid: cws[0][0] = cws[0][1] = cws[0][2] = 0; for(int i = 0; i < number_of_correspondences; i++) for(int j = 0; j < 3; j++) cws[0][j] += pws[3 * i + j]; for(int j = 0; j < 3; j++) cws[0][j] /= number_of_correspondences; // Take C1, C2, and C3 from PCA on the reference points: Eigen::MatrixXd PW0(number_of_correspondences,3); for(int i = 0; i < number_of_correspondences; i++) for(int j = 0; j < 3; j++) PW0(i,j) = pws[3 * i + j] - cws[0][j]; Eigen::MatrixXd PW0tPW0 = PW0.transpose() * PW0; Eigen::JacobiSVD< Eigen::MatrixXd > SVD( PW0tPW0, Eigen::ComputeFullV | Eigen::ComputeFullU ); Eigen::MatrixXd D = SVD.singularValues(); Eigen::MatrixXd Ut = SVD.matrixU().transpose(); for(int i = 1; i < 4; i++) { double k = sqrt(D(i - 1,0) / number_of_correspondences); for(int j = 0; j < 3; j++) cws[i][j] = cws[0][j] + k * Ut((i - 1),j); } } void opengv::absolute_pose::modules::Epnp:: compute_barycentric_coordinates(void) { Eigen::Matrix3d CC; for(int i = 0; i < 3; i++) for(int j = 1; j < 4; j++) CC(i,j-1) = cws[j][i] - cws[0][i]; Eigen::Matrix3d CC_inv = CC.inverse(); for(int i = 0; i < number_of_correspondences; i++) { double * pi = pws + 3 * i; double * a = alphas + 4 * i; for(int j = 0; j < 3; j++) a[1 + j] = CC_inv(j,0) * (pi[0] - cws[0][0]) + CC_inv(j,1) * (pi[1] - cws[0][1]) + CC_inv(j,2) * (pi[2] - cws[0][2]); a[0] = 1.0f - a[1] - a[2] - a[3]; } } void opengv::absolute_pose::modules::Epnp::fill_M( Eigen::MatrixXd & M, const int row, const double * as, const double u, const double v) { for(int i = 0; i < 4; i++) { M(row,3*i) = as[i] * fu; M(row,3*i+1) = 0.0; M(row,3*i+2) = as[i] * (uc - u); M(row+1,3*i) = 0.0; M(row+1,3*i+1) = as[i] * fv; M(row+1,3*i+2) = as[i] * (vc - v); } } void opengv::absolute_pose::modules::Epnp::compute_ccs( const double * betas, const Eigen::MatrixXd & ut) { for(int i = 0; i < 4; i++) ccs[i][0] = ccs[i][1] = ccs[i][2] = 0.0f; for(int i = 0; i < 4; i++) { for(int j = 0; j < 4; j++) for(int k = 0; k < 3; k++) ccs[j][k] += betas[i] * ut(11-i,3 * j + k); } } void opengv::absolute_pose::modules::Epnp::compute_pcs(void) { for(int i = 0; i < number_of_correspondences; i++) { double * a = alphas + 4 * i; double * pc = pcs + 3 * i; for(int j = 0; j < 3; j++) pc[j] = a[0] * ccs[0][j] + a[1] * ccs[1][j] + a[2] * ccs[2][j] + a[3] * ccs[3][j]; } } double opengv::absolute_pose::modules::Epnp::compute_pose( double R[3][3], double t[3]) { choose_control_points(); compute_barycentric_coordinates(); Eigen::MatrixXd M(2*number_of_correspondences,12); for(int i = 0; i < number_of_correspondences; i++) fill_M(M, 2 * i, alphas + 4 * i, us[2 * i], us[2 * i + 1]); Eigen::MatrixXd MtM = M.transpose() * M; Eigen::JacobiSVD< Eigen::MatrixXd > SVD( MtM, Eigen::ComputeFullV | Eigen::ComputeFullU ); Eigen::MatrixXd Ut = SVD.matrixU().transpose(); Eigen::Matrix L_6x10; Eigen::Matrix Rho; compute_L_6x10(Ut,L_6x10); compute_rho(Rho); double Betas[4][4], rep_errors[4]; double Rs[4][3][3], ts[4][3]; find_betas_approx_1(L_6x10, Rho, Betas[1]); gauss_newton(L_6x10, Rho, Betas[1]); rep_errors[1] = compute_R_and_t(Ut, Betas[1], Rs[1], ts[1]); find_betas_approx_2(L_6x10, Rho, Betas[2]); gauss_newton(L_6x10, Rho, Betas[2]); rep_errors[2] = compute_R_and_t(Ut, Betas[2], Rs[2], ts[2]); find_betas_approx_3(L_6x10, Rho, Betas[3]); gauss_newton(L_6x10, Rho, Betas[3]); rep_errors[3] = compute_R_and_t(Ut, Betas[3], Rs[3], ts[3]); int N = 1; if (rep_errors[2] < rep_errors[1]) N = 2; if (rep_errors[3] < rep_errors[N]) N = 3; copy_R_and_t(Rs[N], ts[N], R, t); return rep_errors[N]; } void opengv::absolute_pose::modules::Epnp::copy_R_and_t( const double R_src[3][3], const double t_src[3], double R_dst[3][3], double t_dst[3]) { for(int i = 0; i < 3; i++) { for(int j = 0; j < 3; j++) R_dst[i][j] = R_src[i][j]; t_dst[i] = t_src[i]; } } double opengv::absolute_pose::modules::Epnp::dist2( const double * p1, const double * p2) { return (p1[0] - p2[0]) * (p1[0] - p2[0]) + (p1[1] - p2[1]) * (p1[1] - p2[1]) + (p1[2] - p2[2]) * (p1[2] - p2[2]); } double opengv::absolute_pose::modules::Epnp::dot( const double * v1, const double * v2) { return v1[0] * v2[0] + v1[1] * v2[1] + v1[2] * v2[2]; } double opengv::absolute_pose::modules::Epnp::reprojection_error( const double R[3][3], const double t[3]) { double sum2 = 0.0; for(int i = 0; i < number_of_correspondences; i++) { double * pw = pws + 3 * i; double Xc = dot(R[0], pw) + t[0]; double Yc = dot(R[1], pw) + t[1]; double inv_Zc = 1.0 / (dot(R[2], pw) + t[2]); double ue = uc + fu * Xc * inv_Zc; double ve = vc + fv * Yc * inv_Zc; double u = us[2 * i], v = us[2 * i + 1]; sum2 += sqrt( (u - ue) * (u - ue) + (v - ve) * (v - ve) ); } return sum2 / number_of_correspondences; } void opengv::absolute_pose::modules::Epnp::estimate_R_and_t( double R[3][3], double t[3]) { double pc0[3], pw0[3]; pc0[0] = pc0[1] = pc0[2] = 0.0; pw0[0] = pw0[1] = pw0[2] = 0.0; for(int i = 0; i < number_of_correspondences; i++) { const double * pc = pcs + 3 * i; const double * pw = pws + 3 * i; for(int j = 0; j < 3; j++) { pc0[j] += pc[j]; pw0[j] += pw[j]; } } for(int j = 0; j < 3; j++) { pc0[j] /= number_of_correspondences; pw0[j] /= number_of_correspondences; } Eigen::MatrixXd Abt(3,3); for(int i = 0; i < 3; i++) { for(int j = 0; j < 3; j++) Abt(i,j) = 0.0; } for(int i = 0; i < number_of_correspondences; i++) { double * pc = pcs + 3 * i; double * pw = pws + 3 * i; for(int j = 0; j < 3; j++) { Abt(j,0) += (pc[j] - pc0[j]) * (pw[0] - pw0[0]); Abt(j,1) += (pc[j] - pc0[j]) * (pw[1] - pw0[1]); Abt(j,2) += (pc[j] - pc0[j]) * (pw[2] - pw0[2]); } } Eigen::JacobiSVD< Eigen::MatrixXd > SVD( Abt, Eigen::ComputeFullV | Eigen::ComputeFullU ); Eigen::MatrixXd Abt_u = SVD.matrixU(); Eigen::MatrixXd Abt_v = SVD.matrixV(); for(int i = 0; i < 3; i++) for(int j = 0; j < 3; j++) R[i][j] = Abt_u.row(i) * Abt_v.row(j).transpose(); const double det = R[0][0] * R[1][1] * R[2][2] + R[0][1] * R[1][2] * R[2][0] + R[0][2] * R[1][0] * R[2][1] - R[0][2] * R[1][1] * R[2][0] - R[0][1] * R[1][0] * R[2][2] - R[0][0] * R[1][2] * R[2][1]; //change 1: negative determinant problem is solved by changing Abt_v, not R if (det < 0) { //R[2][0] = -R[2][0]; //R[2][1] = -R[2][1]; //R[2][2] = -R[2][2]; Eigen::MatrixXd Abt_v_prime = Abt_v; Abt_v_prime.col(2) = -Abt_v.col(2); for(int i = 0; i < 3; i++) for(int j = 0; j < 3; j++) R[i][j] = Abt_u.row(i) * Abt_v_prime.row(j).transpose(); } t[0] = pc0[0] - dot(R[0], pw0); t[1] = pc0[1] - dot(R[1], pw0); t[2] = pc0[2] - dot(R[2], pw0); } void opengv::absolute_pose::modules::Epnp::print_pose( const double R[3][3], const double t[3]) { cout << R[0][0] << " " << R[0][1] << " " << R[0][2] << " " << t[0] << endl; cout << R[1][0] << " " << R[1][1] << " " << R[1][2] << " " << t[1] << endl; cout << R[2][0] << " " << R[2][1] << " " << R[2][2] << " " << t[2] << endl; } void opengv::absolute_pose::modules::Epnp::solve_for_sign(void) { //change2: the following method is not independent of the optical system /*if (pcs[2] < 0.0) { for(int i = 0; i < 4; i++) for(int j = 0; j < 3; j++) ccs[i][j] = -ccs[i][j]; for(int i = 0; i < number_of_correspondences; i++) { pcs[3 * i ] = -pcs[3 * i]; pcs[3 * i + 1] = -pcs[3 * i + 1]; pcs[3 * i + 2] = -pcs[3 * i + 2]; } }*/ //change to this (using original depths) if( (pcs[2] < 0.0 && signs[0] > 0) || (pcs[2] > 0.0 && signs[0] < 0) ) { for(int i = 0; i < 4; i++) for(int j = 0; j < 3; j++) ccs[i][j] = -ccs[i][j]; for(int i = 0; i < number_of_correspondences; i++) { pcs[3 * i ] = -pcs[3 * i]; pcs[3 * i + 1] = -pcs[3 * i + 1]; pcs[3 * i + 2] = -pcs[3 * i + 2]; } } } double opengv::absolute_pose::modules::Epnp::compute_R_and_t( const Eigen::MatrixXd & Ut, const double * betas, double R[3][3], double t[3]) { compute_ccs(betas, Ut); compute_pcs(); solve_for_sign(); estimate_R_and_t(R, t); return reprojection_error(R, t); } // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] // betas_approx_1 = [B11 B12 B13 B14] void opengv::absolute_pose::modules::Epnp::find_betas_approx_1( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double * betas) { Eigen::MatrixXd L_6x4(6,4); for(int i = 0; i < 6; i++) { L_6x4(i,0) = L_6x10(i,0); L_6x4(i,1) = L_6x10(i,1); L_6x4(i,2) = L_6x10(i,3); L_6x4(i,3) = L_6x10(i,6); } Eigen::JacobiSVD SVD( L_6x4, Eigen::ComputeFullV | Eigen::ComputeFullU); Eigen::VectorXd Rho_temp = Rho; Eigen::VectorXd b4 = SVD.solve(Rho_temp); if (b4[0] < 0) { betas[0] = sqrt(-b4[0]); betas[1] = -b4[1] / betas[0]; betas[2] = -b4[2] / betas[0]; betas[3] = -b4[3] / betas[0]; } else { betas[0] = sqrt(b4[0]); betas[1] = b4[1] / betas[0]; betas[2] = b4[2] / betas[0]; betas[3] = b4[3] / betas[0]; } } // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] // betas_approx_2 = [B11 B12 B22 ] void opengv::absolute_pose::modules::Epnp::find_betas_approx_2( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double * betas) { Eigen::MatrixXd L_6x3(6,3); for(int i = 0; i < 6; i++) { L_6x3(i,0) = L_6x10(i,0); L_6x3(i,1) = L_6x10(i,1); L_6x3(i,2) = L_6x10(i,2); } Eigen::JacobiSVD SVD( L_6x3, Eigen::ComputeFullV | Eigen::ComputeFullU); Eigen::VectorXd Rho_temp = Rho; Eigen::VectorXd b3 = SVD.solve(Rho_temp); if (b3[0] < 0) { betas[0] = sqrt(-b3[0]); betas[1] = (b3[2] < 0) ? sqrt(-b3[2]) : 0.0; } else { betas[0] = sqrt(b3[0]); betas[1] = (b3[2] > 0) ? sqrt(b3[2]) : 0.0; } if (b3[1] < 0) betas[0] = -betas[0]; betas[2] = 0.0; betas[3] = 0.0; } // betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] // betas_approx_3 = [B11 B12 B22 B13 B23 ] void opengv::absolute_pose::modules::Epnp::find_betas_approx_3( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double * betas) { Eigen::MatrixXd L_6x5(6,5); for(int i = 0; i < 6; i++) { L_6x5(i,0) = L_6x10(i,0); L_6x5(i,1) = L_6x10(i,1); L_6x5(i,2) = L_6x10(i,2); L_6x5(i,3) = L_6x10(i,3); L_6x5(i,4) = L_6x10(i,4); } Eigen::JacobiSVD SVD( L_6x5, Eigen::ComputeFullV | Eigen::ComputeFullU); Eigen::VectorXd Rho_temp = Rho; Eigen::VectorXd b5 = SVD.solve(Rho_temp); if (b5[0] < 0) { betas[0] = sqrt(-b5[0]); betas[1] = (b5[2] < 0) ? sqrt(-b5[2]) : 0.0; } else { betas[0] = sqrt(b5[0]); betas[1] = (b5[2] > 0) ? sqrt(b5[2]) : 0.0; } if (b5[1] < 0) betas[0] = -betas[0]; betas[2] = b5[3] / betas[0]; betas[3] = 0.0; } void opengv::absolute_pose::modules::Epnp::compute_L_6x10( const Eigen::MatrixXd & Ut, Eigen::Matrix & L_6x10 ) { double dv[4][6][3]; for(int i = 0; i < 4; i++) { int a = 0, b = 1; for(int j = 0; j < 6; j++) { dv[i][j][0] = Ut(11-i,3 * a ) - Ut(11-i,3 * b); dv[i][j][1] = Ut(11-i,3 * a + 1) - Ut(11-i,3 * b + 1); dv[i][j][2] = Ut(11-i,3 * a + 2) - Ut(11-i,3 * b + 2); b++; if (b > 3) { a++; b = a + 1; } } } for(int i = 0; i < 6; i++) { L_6x10(i,0) = dot(dv[0][i], dv[0][i]); L_6x10(i,1) = 2.0f * dot(dv[0][i], dv[1][i]); L_6x10(i,2) = dot(dv[1][i], dv[1][i]); L_6x10(i,3) = 2.0f * dot(dv[0][i], dv[2][i]); L_6x10(i,4) = 2.0f * dot(dv[1][i], dv[2][i]); L_6x10(i,5) = dot(dv[2][i], dv[2][i]); L_6x10(i,6) = 2.0f * dot(dv[0][i], dv[3][i]); L_6x10(i,7) = 2.0f * dot(dv[1][i], dv[3][i]); L_6x10(i,8) = 2.0f * dot(dv[2][i], dv[3][i]); L_6x10(i,9) = dot(dv[3][i], dv[3][i]); } } void opengv::absolute_pose::modules::Epnp::compute_rho( Eigen::Matrix & Rho) { Rho[0] = dist2(cws[0], cws[1]); Rho[1] = dist2(cws[0], cws[2]); Rho[2] = dist2(cws[0], cws[3]); Rho[3] = dist2(cws[1], cws[2]); Rho[4] = dist2(cws[1], cws[3]); Rho[5] = dist2(cws[2], cws[3]); } void opengv::absolute_pose::modules::Epnp::compute_A_and_b_gauss_newton( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double betas[4], Eigen::Matrix & A, Eigen::Matrix & b) { for(int i = 0; i < 6; i++) { A(i,0) = 2*L_6x10(i,0)*betas[0] + L_6x10(i,1)*betas[1] + L_6x10(i,3)*betas[2] + L_6x10(i,6)*betas[3]; A(i,1) = L_6x10(i,1)*betas[0] + 2*L_6x10(i,2)*betas[1] + L_6x10(i,4)*betas[2] + L_6x10(i,7)*betas[3]; A(i,2) = L_6x10(i,3)*betas[0] + L_6x10(i,4)*betas[1] + 2*L_6x10(i,5)*betas[2] + L_6x10(i,8)*betas[3]; A(i,3) = L_6x10(i,6)*betas[0] + L_6x10(i,7)*betas[1] + L_6x10(i,8)*betas[2] + 2*L_6x10(i,9)*betas[3]; b(i,0) = Rho[i] - ( L_6x10(i,0) * betas[0] * betas[0] + L_6x10(i,1) * betas[0] * betas[1] + L_6x10(i,2) * betas[1] * betas[1] + L_6x10(i,3) * betas[0] * betas[2] + L_6x10(i,4) * betas[1] * betas[2] + L_6x10(i,5) * betas[2] * betas[2] + L_6x10(i,6) * betas[0] * betas[3] + L_6x10(i,7) * betas[1] * betas[3] + L_6x10(i,8) * betas[2] * betas[3] + L_6x10(i,9) * betas[3] * betas[3]); } } void opengv::absolute_pose::modules::Epnp::gauss_newton( const Eigen::Matrix & L_6x10, const Eigen::Matrix & Rho, double betas[4]) { const int iterations_number = 5; Eigen::Matrix A; Eigen::Matrix B; Eigen::Matrix X; for(int k = 0; k < iterations_number; k++) { compute_A_and_b_gauss_newton(L_6x10,Rho,betas,A,B); qr_solve(A,B,X); for(int i = 0; i < 4; i++) betas[i] += X[i]; } } void opengv::absolute_pose::modules::Epnp::qr_solve( Eigen::Matrix & A_orig, Eigen::Matrix & b, Eigen::Matrix & X) { Eigen::Matrix A = A_orig.transpose(); static int max_nr = 0; static double * A1, * A2; const int nr = A_orig.rows(); const int nc = A_orig.cols(); if (max_nr != 0 && max_nr < nr) { delete [] A1; delete [] A2; } if (max_nr < nr) { max_nr = nr; A1 = new double[nr]; A2 = new double[nr]; } double * pA = A.data(), * ppAkk = pA; for(int k = 0; k < nc; k++) { double * ppAik = ppAkk, eta = fabs(*ppAik); for(int i = k + 1; i < nr; i++) { double elt = fabs(*ppAik); if (eta < elt) eta = elt; ppAik += nc; } if (eta == 0) { A1[k] = A2[k] = 0.0; cerr << "God damnit, A is singular, this shouldn't happen." << endl; return; } else { double * ppAik = ppAkk, sum = 0.0, inv_eta = 1. / eta; for(int i = k; i < nr; i++) { *ppAik *= inv_eta; sum += *ppAik * *ppAik; ppAik += nc; } double sigma = sqrt(sum); if (*ppAkk < 0) sigma = -sigma; *ppAkk += sigma; A1[k] = sigma * *ppAkk; A2[k] = -eta * sigma; for(int j = k + 1; j < nc; j++) { double * ppAik = ppAkk, sum = 0; for(int i = k; i < nr; i++) { sum += *ppAik * ppAik[j - k]; ppAik += nc; } double tau = sum / A1[k]; ppAik = ppAkk; for(int i = k; i < nr; i++) { ppAik[j - k] -= tau * *ppAik; ppAik += nc; } } } ppAkk += nc + 1; } // b <- Qt b double * ppAjj = pA, * pb = b.data(); for(int j = 0; j < nc; j++) { double * ppAij = ppAjj, tau = 0; for(int i = j; i < nr; i++) { tau += *ppAij * pb[i]; ppAij += nc; } tau /= A1[j]; ppAij = ppAjj; for(int i = j; i < nr; i++) { pb[i] -= tau * *ppAij; ppAij += nc; } ppAjj += nc + 1; } // X = R-1 b double * pX = X.data(); pX[nc - 1] = pb[nc - 1] / A2[nc - 1]; for(int i = nc - 2; i >= 0; i--) { double * ppAij = pA + i * nc + (i + 1), sum = 0; for(int j = i + 1; j < nc; j++) { sum += *ppAij * pX[j]; ppAij++; } pX[i] = (pb[i] - sum) / A2[i]; } } void opengv::absolute_pose::modules::Epnp::relative_error( double & rot_err, double & transl_err, const double Rtrue[3][3], const double ttrue[3], const double Rest[3][3], const double test[3]) { double qtrue[4], qest[4]; mat_to_quat(Rtrue, qtrue); mat_to_quat(Rest, qest); double rot_err1 = sqrt((qtrue[0] - qest[0]) * (qtrue[0] - qest[0]) + (qtrue[1] - qest[1]) * (qtrue[1] - qest[1]) + (qtrue[2] - qest[2]) * (qtrue[2] - qest[2]) + (qtrue[3] - qest[3]) * (qtrue[3] - qest[3])) / sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]); double rot_err2 = sqrt((qtrue[0] + qest[0]) * (qtrue[0] + qest[0]) + (qtrue[1] + qest[1]) * (qtrue[1] + qest[1]) + (qtrue[2] + qest[2]) * (qtrue[2] + qest[2]) + (qtrue[3] + qest[3]) * (qtrue[3] + qest[3]) ) / sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]); rot_err = min(rot_err1,rot_err2); transl_err = sqrt((ttrue[0] - test[0]) * (ttrue[0] - test[0]) + (ttrue[1] - test[1]) * (ttrue[1] - test[1]) + (ttrue[2] - test[2]) * (ttrue[2] - test[2])) / sqrt(ttrue[0] * ttrue[0] + ttrue[1] * ttrue[1] + ttrue[2] * ttrue[2]); } void opengv::absolute_pose::modules::Epnp::mat_to_quat( const double R[3][3], double q[4]) { double tr = R[0][0] + R[1][1] + R[2][2]; double n4; if (tr > 0.0f) { q[0] = R[1][2] - R[2][1]; q[1] = R[2][0] - R[0][2]; q[2] = R[0][1] - R[1][0]; q[3] = tr + 1.0f; n4 = q[3]; } else if ( (R[0][0] > R[1][1]) && (R[0][0] > R[2][2]) ) { q[0] = 1.0f + R[0][0] - R[1][1] - R[2][2]; q[1] = R[1][0] + R[0][1]; q[2] = R[2][0] + R[0][2]; q[3] = R[1][2] - R[2][1]; n4 = q[0]; } else if (R[1][1] > R[2][2]) { q[0] = R[1][0] + R[0][1]; q[1] = 1.0f + R[1][1] - R[0][0] - R[2][2]; q[2] = R[2][1] + R[1][2]; q[3] = R[2][0] - R[0][2]; n4 = q[1]; } else { q[0] = R[2][0] + R[0][2]; q[1] = R[2][1] + R[1][2]; q[2] = 1.0f + R[2][2] - R[0][0] - R[1][1]; q[3] = R[0][1] - R[1][0]; n4 = q[2]; } double scale = 0.5f / double(sqrt(n4)); q[0] *= scale; q[1] *= scale; q[2] *= scale; q[3] *= scale; } opengv/src/absolute_pose/modules/gpnp4/0000775016516101651610000000000013344612246017142 5ustar dimadimaopengv/src/absolute_pose/modules/gpnp4/reductors.cpp0000664016516101651610000013465613344612246021677 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp4::groebnerRow5_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,23) / groebnerMatrix(5,23); groebnerMatrix(targetRow,23) = 0.0; groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(5,24); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(5,25); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(5,26); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(5,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(5,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(5,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(5,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(5,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(5,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(5,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(5,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(5,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(5,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow6_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,24) / groebnerMatrix(6,24); groebnerMatrix(targetRow,24) = 0.0; groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(6,25); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(6,26); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(6,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(6,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(6,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(6,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(6,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(6,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(6,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(6,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(6,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(6,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow7_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,25) / groebnerMatrix(7,25); groebnerMatrix(targetRow,25) = 0.0; groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(7,26); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(7,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(7,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(7,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(7,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(7,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(7,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(7,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(7,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(7,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(7,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow7_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,9) / groebnerMatrix(7,25); groebnerMatrix(targetRow,9) = 0.0; groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(7,26); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(7,27); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(7,28); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(7,29); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(7,30); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(7,31); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(7,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(7,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(7,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(7,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(7,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow8_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,10) / groebnerMatrix(8,26); groebnerMatrix(targetRow,10) = 0.0; groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(8,27); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(8,28); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(8,29); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(8,30); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(8,31); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(8,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(8,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(8,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(8,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(8,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow5_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,13) / groebnerMatrix(5,23); groebnerMatrix(targetRow,13) = 0.0; groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(5,24); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(5,25); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(5,26); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(5,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(5,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(5,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(5,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(5,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(5,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(5,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(5,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(5,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(5,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow6_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,14) / groebnerMatrix(6,24); groebnerMatrix(targetRow,14) = 0.0; groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(6,25); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(6,26); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(6,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(6,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(6,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(6,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(6,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(6,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(6,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(6,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(6,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(6,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow7_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,15) / groebnerMatrix(7,25); groebnerMatrix(targetRow,15) = 0.0; groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(7,26); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(7,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(7,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(7,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(7,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(7,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(7,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(7,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(7,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(7,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(7,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow8_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,16) / groebnerMatrix(8,26); groebnerMatrix(targetRow,16) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(8,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(8,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(8,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(8,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(8,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(8,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(8,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(8,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(8,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(8,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow8_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,26) / groebnerMatrix(8,26); groebnerMatrix(targetRow,26) = 0.0; groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(8,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(8,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(8,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(8,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(8,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(8,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(8,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(8,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(8,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(8,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow6_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,8) / groebnerMatrix(6,24); groebnerMatrix(targetRow,8) = 0.0; groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(6,25); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(6,26); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(6,27); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(6,28); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(6,29); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(6,30); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(6,31); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(6,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(6,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(6,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(6,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(6,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow9_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,11) / groebnerMatrix(9,11); groebnerMatrix(targetRow,11) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(9,17); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(9,18); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(9,19); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(9,20); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(9,21); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(9,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(9,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(9,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(9,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(9,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(9,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(9,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(9,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(9,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(9,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow4_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,12) / groebnerMatrix(4,22); groebnerMatrix(targetRow,12) = 0.0; groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(4,23); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(4,24); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(4,25); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(4,26); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(4,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(4,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(4,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(4,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(4,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(4,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(4,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(4,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(4,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(4,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow10_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,17) / groebnerMatrix(10,17); groebnerMatrix(targetRow,17) = 0.0; groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(10,18); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(10,19); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(10,20); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(10,21); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(10,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(10,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(10,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(10,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(10,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(10,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(10,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(10,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(10,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(10,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow4_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,22) / groebnerMatrix(4,22); groebnerMatrix(targetRow,22) = 0.0; groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(4,23); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(4,24); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(4,25); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(4,26); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(4,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(4,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(4,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(4,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(4,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(4,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(4,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(4,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(4,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(4,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow5_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,7) / groebnerMatrix(5,23); groebnerMatrix(targetRow,7) = 0.0; groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(5,24); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(5,25); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(5,26); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(5,27); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(5,28); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(5,29); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(5,30); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(5,31); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(5,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(5,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(5,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(5,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(5,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow11_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,18) / groebnerMatrix(11,18); groebnerMatrix(targetRow,18) = 0.0; groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(11,19); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(11,20); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(11,21); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(11,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(11,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(11,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(11,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(11,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(11,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(11,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(11,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(11,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(11,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow6_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,5) / groebnerMatrix(6,24); groebnerMatrix(targetRow,5) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(6,25); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(6,26); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(6,27); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(6,28); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(6,29); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(6,30); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(6,31); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(6,32); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(6,33); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(6,34); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(6,35); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(6,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow4_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,6) / groebnerMatrix(4,22); groebnerMatrix(targetRow,6) = 0.0; groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(4,23); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(4,24); groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(4,25); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(4,26); groebnerMatrix(targetRow,11) -= factor * groebnerMatrix(4,27); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(4,28); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(4,29); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(4,30); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(4,31); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(4,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(4,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(4,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(4,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(4,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow12_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,19) / groebnerMatrix(12,19); groebnerMatrix(targetRow,19) = 0.0; groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(12,20); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(12,21); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(12,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(12,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(12,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(12,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(12,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(12,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(12,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(12,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(12,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(12,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow5_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,4) / groebnerMatrix(5,23); groebnerMatrix(targetRow,4) = 0.0; groebnerMatrix(targetRow,5) -= factor * groebnerMatrix(5,24); groebnerMatrix(targetRow,7) -= factor * groebnerMatrix(5,25); groebnerMatrix(targetRow,8) -= factor * groebnerMatrix(5,26); groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(5,27); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(5,28); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(5,29); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(5,30); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(5,31); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(5,32); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(5,33); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(5,34); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(5,35); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(5,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow13_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,20) / groebnerMatrix(13,20); groebnerMatrix(targetRow,20) = 0.0; groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(13,21); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(13,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(13,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(13,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(13,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(13,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(13,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(13,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(13,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(13,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(13,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow14_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,3) / groebnerMatrix(14,21); groebnerMatrix(targetRow,3) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(14,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(14,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(14,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(14,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(14,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(14,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(14,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(14,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(14,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(14,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow14_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,21) / groebnerMatrix(14,21); groebnerMatrix(targetRow,21) = 0.0; groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(14,27); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(14,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(14,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(14,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(14,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(14,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(14,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(14,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(14,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(14,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow13_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,2) / groebnerMatrix(13,20); groebnerMatrix(targetRow,2) = 0.0; groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(13,21); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(13,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(13,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(13,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(13,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(13,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(13,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(13,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(13,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(13,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(13,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow15_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,11) / groebnerMatrix(15,27); groebnerMatrix(targetRow,11) = 0.0; groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(15,28); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(15,29); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(15,30); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(15,31); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(15,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(15,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(15,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(15,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(15,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow15_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,17) / groebnerMatrix(15,27); groebnerMatrix(targetRow,17) = 0.0; groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(15,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(15,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(15,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(15,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(15,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(15,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(15,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(15,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(15,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow15_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,27) / groebnerMatrix(15,27); groebnerMatrix(targetRow,27) = 0.0; groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(15,28); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(15,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(15,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(15,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(15,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(15,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(15,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(15,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(15,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow12_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(12,19); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,2) -= factor * groebnerMatrix(12,20); groebnerMatrix(targetRow,3) -= factor * groebnerMatrix(12,21); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(12,27); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(12,28); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(12,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(12,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(12,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(12,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(12,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(12,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(12,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(12,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow16_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,18) / groebnerMatrix(16,28); groebnerMatrix(targetRow,18) = 0.0; groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(16,29); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(16,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(16,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(16,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(16,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(16,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(16,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(16,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow16_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,28) / groebnerMatrix(16,28); groebnerMatrix(targetRow,28) = 0.0; groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(16,29); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(16,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(16,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(16,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(16,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(16,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(16,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(16,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow14_0001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,0) / groebnerMatrix(14,21); groebnerMatrix(targetRow,0) = 0.0; groebnerMatrix(targetRow,9) -= factor * groebnerMatrix(14,27); groebnerMatrix(targetRow,12) -= factor * groebnerMatrix(14,28); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(14,29); groebnerMatrix(targetRow,15) -= factor * groebnerMatrix(14,30); groebnerMatrix(targetRow,18) -= factor * groebnerMatrix(14,31); groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(14,32); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(14,33); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(14,34); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(14,35); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(14,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow14_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(14,21); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,10) -= factor * groebnerMatrix(14,27); groebnerMatrix(targetRow,13) -= factor * groebnerMatrix(14,28); groebnerMatrix(targetRow,14) -= factor * groebnerMatrix(14,29); groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(14,30); groebnerMatrix(targetRow,19) -= factor * groebnerMatrix(14,31); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(14,32); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(14,33); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(14,34); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(14,35); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(14,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow17_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,19) / groebnerMatrix(17,29); groebnerMatrix(targetRow,19) = 0.0; groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(17,30); groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(17,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(17,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(17,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(17,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(17,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(17,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow17_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,29) / groebnerMatrix(17,29); groebnerMatrix(targetRow,29) = 0.0; groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(17,30); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(17,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(17,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(17,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(17,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(17,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(17,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow18_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,30) / groebnerMatrix(18,30); groebnerMatrix(targetRow,30) = 0.0; groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(18,31); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(18,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(18,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(18,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(18,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(18,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow18_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,20) / groebnerMatrix(18,30); groebnerMatrix(targetRow,20) = 0.0; groebnerMatrix(targetRow,21) -= factor * groebnerMatrix(18,31); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(18,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(18,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(18,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(18,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(18,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow19_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,21) / groebnerMatrix(19,31); groebnerMatrix(targetRow,21) = 0.0; groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(19,32); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(19,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(19,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(19,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(19,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow19_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,31) / groebnerMatrix(19,31); groebnerMatrix(targetRow,31) = 0.0; groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(19,32); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(19,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(19,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(19,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(19,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow20_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,28) / groebnerMatrix(20,32); groebnerMatrix(targetRow,28) = 0.0; groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(20,33); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(20,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(20,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(20,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow20_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,32) / groebnerMatrix(20,32); groebnerMatrix(targetRow,32) = 0.0; groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(20,33); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(20,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(20,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(20,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow19_0001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,18) / groebnerMatrix(19,31); groebnerMatrix(targetRow,18) = 0.0; groebnerMatrix(targetRow,22) -= factor * groebnerMatrix(19,32); groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(19,33); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(19,34); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(19,35); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(19,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow19_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,19) / groebnerMatrix(19,31); groebnerMatrix(targetRow,19) = 0.0; groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(19,32); groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(19,33); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(19,34); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(19,35); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(19,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow20_0001_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,22) / groebnerMatrix(20,32); groebnerMatrix(targetRow,22) = 0.0; groebnerMatrix(targetRow,23) -= factor * groebnerMatrix(20,33); groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(20,34); groebnerMatrix(targetRow,28) -= factor * groebnerMatrix(20,35); groebnerMatrix(targetRow,32) -= factor * groebnerMatrix(20,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow20_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,23) / groebnerMatrix(20,32); groebnerMatrix(targetRow,23) = 0.0; groebnerMatrix(targetRow,24) -= factor * groebnerMatrix(20,33); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(20,34); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(20,35); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(20,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow21_0010_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,24) / groebnerMatrix(21,33); groebnerMatrix(targetRow,24) = 0.0; groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(21,34); groebnerMatrix(targetRow,29) -= factor * groebnerMatrix(21,35); groebnerMatrix(targetRow,33) -= factor * groebnerMatrix(21,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow20_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,25) / groebnerMatrix(20,32); groebnerMatrix(targetRow,25) = 0.0; groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(20,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(20,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(20,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(20,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow21_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,26) / groebnerMatrix(21,33); groebnerMatrix(targetRow,26) = 0.0; groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(21,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(21,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(21,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow21_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,29) / groebnerMatrix(21,33); groebnerMatrix(targetRow,29) = 0.0; groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(21,34); groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(21,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(21,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow21_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,33) / groebnerMatrix(21,33); groebnerMatrix(targetRow,33) = 0.0; groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(21,34); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(21,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(21,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow20_1100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,15) / groebnerMatrix(20,32); groebnerMatrix(targetRow,15) = 0.0; groebnerMatrix(targetRow,16) -= factor * groebnerMatrix(20,33); groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(20,34); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(20,35); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(20,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow21_1100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,16) / groebnerMatrix(21,33); groebnerMatrix(targetRow,16) = 0.0; groebnerMatrix(targetRow,17) -= factor * groebnerMatrix(21,34); groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(21,35); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(21,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow22_1100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,17) / groebnerMatrix(22,34); groebnerMatrix(targetRow,17) = 0.0; groebnerMatrix(targetRow,20) -= factor * groebnerMatrix(22,35); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(22,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow19_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,20) / groebnerMatrix(19,31); groebnerMatrix(targetRow,20) = 0.0; groebnerMatrix(targetRow,25) -= factor * groebnerMatrix(19,32); groebnerMatrix(targetRow,26) -= factor * groebnerMatrix(19,33); groebnerMatrix(targetRow,27) -= factor * groebnerMatrix(19,34); groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(19,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(19,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow22_0100_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,27) / groebnerMatrix(22,34); groebnerMatrix(targetRow,27) = 0.0; groebnerMatrix(targetRow,30) -= factor * groebnerMatrix(22,35); groebnerMatrix(targetRow,34) -= factor * groebnerMatrix(22,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow22_1000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,30) / groebnerMatrix(22,34); groebnerMatrix(targetRow,30) = 0.0; groebnerMatrix(targetRow,31) -= factor * groebnerMatrix(22,35); groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(22,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow22_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,34) / groebnerMatrix(22,34); groebnerMatrix(targetRow,34) = 0.0; groebnerMatrix(targetRow,35) -= factor * groebnerMatrix(22,35); groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(22,36); } void opengv::absolute_pose::modules::gpnp4::groebnerRow23_0000_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,35) / groebnerMatrix(23,35); groebnerMatrix(targetRow,35) = 0.0; groebnerMatrix(targetRow,36) -= factor * groebnerMatrix(23,36); } opengv/src/absolute_pose/modules/gpnp4/spolynomials.cpp0000664016516101651610000010320213344612246022375 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp4::sPolynomial5( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(5,23) = (groebnerMatrix(0,23)/(groebnerMatrix(0,22))-groebnerMatrix(1,23)/(groebnerMatrix(1,22))); groebnerMatrix(5,24) = (groebnerMatrix(0,24)/(groebnerMatrix(0,22))-groebnerMatrix(1,24)/(groebnerMatrix(1,22))); groebnerMatrix(5,25) = (groebnerMatrix(0,25)/(groebnerMatrix(0,22))-groebnerMatrix(1,25)/(groebnerMatrix(1,22))); groebnerMatrix(5,26) = (groebnerMatrix(0,26)/(groebnerMatrix(0,22))-groebnerMatrix(1,26)/(groebnerMatrix(1,22))); groebnerMatrix(5,27) = (groebnerMatrix(0,27)/(groebnerMatrix(0,22))-groebnerMatrix(1,27)/(groebnerMatrix(1,22))); groebnerMatrix(5,28) = (groebnerMatrix(0,28)/(groebnerMatrix(0,22))-groebnerMatrix(1,28)/(groebnerMatrix(1,22))); groebnerMatrix(5,29) = (groebnerMatrix(0,29)/(groebnerMatrix(0,22))-groebnerMatrix(1,29)/(groebnerMatrix(1,22))); groebnerMatrix(5,30) = (groebnerMatrix(0,30)/(groebnerMatrix(0,22))-groebnerMatrix(1,30)/(groebnerMatrix(1,22))); groebnerMatrix(5,31) = (groebnerMatrix(0,31)/(groebnerMatrix(0,22))-groebnerMatrix(1,31)/(groebnerMatrix(1,22))); groebnerMatrix(5,32) = (groebnerMatrix(0,32)/(groebnerMatrix(0,22))-groebnerMatrix(1,32)/(groebnerMatrix(1,22))); groebnerMatrix(5,33) = (groebnerMatrix(0,33)/(groebnerMatrix(0,22))-groebnerMatrix(1,33)/(groebnerMatrix(1,22))); groebnerMatrix(5,34) = (groebnerMatrix(0,34)/(groebnerMatrix(0,22))-groebnerMatrix(1,34)/(groebnerMatrix(1,22))); groebnerMatrix(5,35) = (groebnerMatrix(0,35)/(groebnerMatrix(0,22))-groebnerMatrix(1,35)/(groebnerMatrix(1,22))); groebnerMatrix(5,36) = (groebnerMatrix(0,36)/(groebnerMatrix(0,22))-groebnerMatrix(1,36)/(groebnerMatrix(1,22))); } void opengv::absolute_pose::modules::gpnp4::sPolynomial6( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(6,23) = (groebnerMatrix(1,23)/(groebnerMatrix(1,22))-groebnerMatrix(2,23)/(groebnerMatrix(2,22))); groebnerMatrix(6,24) = (groebnerMatrix(1,24)/(groebnerMatrix(1,22))-groebnerMatrix(2,24)/(groebnerMatrix(2,22))); groebnerMatrix(6,25) = (groebnerMatrix(1,25)/(groebnerMatrix(1,22))-groebnerMatrix(2,25)/(groebnerMatrix(2,22))); groebnerMatrix(6,26) = (groebnerMatrix(1,26)/(groebnerMatrix(1,22))-groebnerMatrix(2,26)/(groebnerMatrix(2,22))); groebnerMatrix(6,27) = (groebnerMatrix(1,27)/(groebnerMatrix(1,22))-groebnerMatrix(2,27)/(groebnerMatrix(2,22))); groebnerMatrix(6,28) = (groebnerMatrix(1,28)/(groebnerMatrix(1,22))-groebnerMatrix(2,28)/(groebnerMatrix(2,22))); groebnerMatrix(6,29) = (groebnerMatrix(1,29)/(groebnerMatrix(1,22))-groebnerMatrix(2,29)/(groebnerMatrix(2,22))); groebnerMatrix(6,30) = (groebnerMatrix(1,30)/(groebnerMatrix(1,22))-groebnerMatrix(2,30)/(groebnerMatrix(2,22))); groebnerMatrix(6,31) = (groebnerMatrix(1,31)/(groebnerMatrix(1,22))-groebnerMatrix(2,31)/(groebnerMatrix(2,22))); groebnerMatrix(6,32) = (groebnerMatrix(1,32)/(groebnerMatrix(1,22))-groebnerMatrix(2,32)/(groebnerMatrix(2,22))); groebnerMatrix(6,33) = (groebnerMatrix(1,33)/(groebnerMatrix(1,22))-groebnerMatrix(2,33)/(groebnerMatrix(2,22))); groebnerMatrix(6,34) = (groebnerMatrix(1,34)/(groebnerMatrix(1,22))-groebnerMatrix(2,34)/(groebnerMatrix(2,22))); groebnerMatrix(6,35) = (groebnerMatrix(1,35)/(groebnerMatrix(1,22))-groebnerMatrix(2,35)/(groebnerMatrix(2,22))); groebnerMatrix(6,36) = (groebnerMatrix(1,36)/(groebnerMatrix(1,22))-groebnerMatrix(2,36)/(groebnerMatrix(2,22))); } void opengv::absolute_pose::modules::gpnp4::sPolynomial7( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(7,23) = (groebnerMatrix(2,23)/(groebnerMatrix(2,22))-groebnerMatrix(3,23)/(groebnerMatrix(3,22))); groebnerMatrix(7,24) = (groebnerMatrix(2,24)/(groebnerMatrix(2,22))-groebnerMatrix(3,24)/(groebnerMatrix(3,22))); groebnerMatrix(7,25) = (groebnerMatrix(2,25)/(groebnerMatrix(2,22))-groebnerMatrix(3,25)/(groebnerMatrix(3,22))); groebnerMatrix(7,26) = (groebnerMatrix(2,26)/(groebnerMatrix(2,22))-groebnerMatrix(3,26)/(groebnerMatrix(3,22))); groebnerMatrix(7,27) = (groebnerMatrix(2,27)/(groebnerMatrix(2,22))-groebnerMatrix(3,27)/(groebnerMatrix(3,22))); groebnerMatrix(7,28) = (groebnerMatrix(2,28)/(groebnerMatrix(2,22))-groebnerMatrix(3,28)/(groebnerMatrix(3,22))); groebnerMatrix(7,29) = (groebnerMatrix(2,29)/(groebnerMatrix(2,22))-groebnerMatrix(3,29)/(groebnerMatrix(3,22))); groebnerMatrix(7,30) = (groebnerMatrix(2,30)/(groebnerMatrix(2,22))-groebnerMatrix(3,30)/(groebnerMatrix(3,22))); groebnerMatrix(7,31) = (groebnerMatrix(2,31)/(groebnerMatrix(2,22))-groebnerMatrix(3,31)/(groebnerMatrix(3,22))); groebnerMatrix(7,32) = (groebnerMatrix(2,32)/(groebnerMatrix(2,22))-groebnerMatrix(3,32)/(groebnerMatrix(3,22))); groebnerMatrix(7,33) = (groebnerMatrix(2,33)/(groebnerMatrix(2,22))-groebnerMatrix(3,33)/(groebnerMatrix(3,22))); groebnerMatrix(7,34) = (groebnerMatrix(2,34)/(groebnerMatrix(2,22))-groebnerMatrix(3,34)/(groebnerMatrix(3,22))); groebnerMatrix(7,35) = (groebnerMatrix(2,35)/(groebnerMatrix(2,22))-groebnerMatrix(3,35)/(groebnerMatrix(3,22))); groebnerMatrix(7,36) = (groebnerMatrix(2,36)/(groebnerMatrix(2,22))-groebnerMatrix(3,36)/(groebnerMatrix(3,22))); } void opengv::absolute_pose::modules::gpnp4::sPolynomial8( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(8,23) = (groebnerMatrix(3,23)/(groebnerMatrix(3,22))-groebnerMatrix(4,23)/(groebnerMatrix(4,22))); groebnerMatrix(8,24) = (groebnerMatrix(3,24)/(groebnerMatrix(3,22))-groebnerMatrix(4,24)/(groebnerMatrix(4,22))); groebnerMatrix(8,25) = (groebnerMatrix(3,25)/(groebnerMatrix(3,22))-groebnerMatrix(4,25)/(groebnerMatrix(4,22))); groebnerMatrix(8,26) = (groebnerMatrix(3,26)/(groebnerMatrix(3,22))-groebnerMatrix(4,26)/(groebnerMatrix(4,22))); groebnerMatrix(8,27) = (groebnerMatrix(3,27)/(groebnerMatrix(3,22))-groebnerMatrix(4,27)/(groebnerMatrix(4,22))); groebnerMatrix(8,28) = (groebnerMatrix(3,28)/(groebnerMatrix(3,22))-groebnerMatrix(4,28)/(groebnerMatrix(4,22))); groebnerMatrix(8,29) = (groebnerMatrix(3,29)/(groebnerMatrix(3,22))-groebnerMatrix(4,29)/(groebnerMatrix(4,22))); groebnerMatrix(8,30) = (groebnerMatrix(3,30)/(groebnerMatrix(3,22))-groebnerMatrix(4,30)/(groebnerMatrix(4,22))); groebnerMatrix(8,31) = (groebnerMatrix(3,31)/(groebnerMatrix(3,22))-groebnerMatrix(4,31)/(groebnerMatrix(4,22))); groebnerMatrix(8,32) = (groebnerMatrix(3,32)/(groebnerMatrix(3,22))-groebnerMatrix(4,32)/(groebnerMatrix(4,22))); groebnerMatrix(8,33) = (groebnerMatrix(3,33)/(groebnerMatrix(3,22))-groebnerMatrix(4,33)/(groebnerMatrix(4,22))); groebnerMatrix(8,34) = (groebnerMatrix(3,34)/(groebnerMatrix(3,22))-groebnerMatrix(4,34)/(groebnerMatrix(4,22))); groebnerMatrix(8,35) = (groebnerMatrix(3,35)/(groebnerMatrix(3,22))-groebnerMatrix(4,35)/(groebnerMatrix(4,22))); groebnerMatrix(8,36) = (groebnerMatrix(3,36)/(groebnerMatrix(3,22))-groebnerMatrix(4,36)/(groebnerMatrix(4,22))); } void opengv::absolute_pose::modules::gpnp4::sPolynomial9( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(9,9) = groebnerMatrix(6,25)/(groebnerMatrix(6,24)); groebnerMatrix(9,10) = (groebnerMatrix(6,26)/(groebnerMatrix(6,24))-groebnerMatrix(8,27)/(groebnerMatrix(8,26))); groebnerMatrix(9,11) = groebnerMatrix(6,27)/(groebnerMatrix(6,24)); groebnerMatrix(9,13) = -groebnerMatrix(8,28)/(groebnerMatrix(8,26)); groebnerMatrix(9,14) = -groebnerMatrix(8,29)/(groebnerMatrix(8,26)); groebnerMatrix(9,15) = groebnerMatrix(6,28)/(groebnerMatrix(6,24)); groebnerMatrix(9,16) = (groebnerMatrix(6,29)/(groebnerMatrix(6,24))-groebnerMatrix(8,30)/(groebnerMatrix(8,26))); groebnerMatrix(9,17) = groebnerMatrix(6,30)/(groebnerMatrix(6,24)); groebnerMatrix(9,19) = -groebnerMatrix(8,31)/(groebnerMatrix(8,26)); groebnerMatrix(9,20) = groebnerMatrix(6,31)/(groebnerMatrix(6,24)); groebnerMatrix(9,23) = -groebnerMatrix(8,32)/(groebnerMatrix(8,26)); groebnerMatrix(9,24) = -groebnerMatrix(8,33)/(groebnerMatrix(8,26)); groebnerMatrix(9,25) = groebnerMatrix(6,32)/(groebnerMatrix(6,24)); groebnerMatrix(9,26) = (groebnerMatrix(6,33)/(groebnerMatrix(6,24))-groebnerMatrix(8,34)/(groebnerMatrix(8,26))); groebnerMatrix(9,27) = groebnerMatrix(6,34)/(groebnerMatrix(6,24)); groebnerMatrix(9,29) = -groebnerMatrix(8,35)/(groebnerMatrix(8,26)); groebnerMatrix(9,30) = groebnerMatrix(6,35)/(groebnerMatrix(6,24)); groebnerMatrix(9,33) = -groebnerMatrix(8,36)/(groebnerMatrix(8,26)); groebnerMatrix(9,34) = groebnerMatrix(6,36)/(groebnerMatrix(6,24)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial10( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(10,8) = (groebnerMatrix(5,24)/(groebnerMatrix(5,23))-groebnerMatrix(7,26)/(groebnerMatrix(7,25))); groebnerMatrix(10,9) = groebnerMatrix(5,25)/(groebnerMatrix(5,23)); groebnerMatrix(10,10) = (groebnerMatrix(5,26)/(groebnerMatrix(5,23))-groebnerMatrix(7,27)/(groebnerMatrix(7,25))); groebnerMatrix(10,11) = groebnerMatrix(5,27)/(groebnerMatrix(5,23)); groebnerMatrix(10,13) = -groebnerMatrix(7,28)/(groebnerMatrix(7,25)); groebnerMatrix(10,14) = -groebnerMatrix(7,29)/(groebnerMatrix(7,25)); groebnerMatrix(10,15) = groebnerMatrix(5,28)/(groebnerMatrix(5,23)); groebnerMatrix(10,16) = (groebnerMatrix(5,29)/(groebnerMatrix(5,23))-groebnerMatrix(7,30)/(groebnerMatrix(7,25))); groebnerMatrix(10,17) = groebnerMatrix(5,30)/(groebnerMatrix(5,23)); groebnerMatrix(10,19) = -groebnerMatrix(7,31)/(groebnerMatrix(7,25)); groebnerMatrix(10,20) = groebnerMatrix(5,31)/(groebnerMatrix(5,23)); groebnerMatrix(10,23) = -groebnerMatrix(7,32)/(groebnerMatrix(7,25)); groebnerMatrix(10,24) = -groebnerMatrix(7,33)/(groebnerMatrix(7,25)); groebnerMatrix(10,25) = groebnerMatrix(5,32)/(groebnerMatrix(5,23)); groebnerMatrix(10,26) = (groebnerMatrix(5,33)/(groebnerMatrix(5,23))-groebnerMatrix(7,34)/(groebnerMatrix(7,25))); groebnerMatrix(10,27) = groebnerMatrix(5,34)/(groebnerMatrix(5,23)); groebnerMatrix(10,29) = -groebnerMatrix(7,35)/(groebnerMatrix(7,25)); groebnerMatrix(10,30) = groebnerMatrix(5,35)/(groebnerMatrix(5,23)); groebnerMatrix(10,33) = -groebnerMatrix(7,36)/(groebnerMatrix(7,25)); groebnerMatrix(10,34) = groebnerMatrix(5,36)/(groebnerMatrix(5,23)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial11( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(11,8) = groebnerMatrix(5,24)/(groebnerMatrix(5,23)); groebnerMatrix(11,9) = (groebnerMatrix(5,25)/(groebnerMatrix(5,23))-groebnerMatrix(8,27)/(groebnerMatrix(8,26))); groebnerMatrix(11,10) = groebnerMatrix(5,26)/(groebnerMatrix(5,23)); groebnerMatrix(11,11) = groebnerMatrix(5,27)/(groebnerMatrix(5,23)); groebnerMatrix(11,12) = -groebnerMatrix(8,28)/(groebnerMatrix(8,26)); groebnerMatrix(11,13) = -groebnerMatrix(8,29)/(groebnerMatrix(8,26)); groebnerMatrix(11,15) = (groebnerMatrix(5,28)/(groebnerMatrix(5,23))-groebnerMatrix(8,30)/(groebnerMatrix(8,26))); groebnerMatrix(11,16) = groebnerMatrix(5,29)/(groebnerMatrix(5,23)); groebnerMatrix(11,17) = groebnerMatrix(5,30)/(groebnerMatrix(5,23)); groebnerMatrix(11,18) = -groebnerMatrix(8,31)/(groebnerMatrix(8,26)); groebnerMatrix(11,20) = groebnerMatrix(5,31)/(groebnerMatrix(5,23)); groebnerMatrix(11,22) = -groebnerMatrix(8,32)/(groebnerMatrix(8,26)); groebnerMatrix(11,23) = -groebnerMatrix(8,33)/(groebnerMatrix(8,26)); groebnerMatrix(11,25) = (groebnerMatrix(5,32)/(groebnerMatrix(5,23))-groebnerMatrix(8,34)/(groebnerMatrix(8,26))); groebnerMatrix(11,26) = groebnerMatrix(5,33)/(groebnerMatrix(5,23)); groebnerMatrix(11,27) = groebnerMatrix(5,34)/(groebnerMatrix(5,23)); groebnerMatrix(11,28) = -groebnerMatrix(8,35)/(groebnerMatrix(8,26)); groebnerMatrix(11,30) = groebnerMatrix(5,35)/(groebnerMatrix(5,23)); groebnerMatrix(11,32) = -groebnerMatrix(8,36)/(groebnerMatrix(8,26)); groebnerMatrix(11,34) = groebnerMatrix(5,36)/(groebnerMatrix(5,23)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial12( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(12,7) = (groebnerMatrix(4,23)/(groebnerMatrix(4,22))-groebnerMatrix(7,26)/(groebnerMatrix(7,25))); groebnerMatrix(12,8) = groebnerMatrix(4,24)/(groebnerMatrix(4,22)); groebnerMatrix(12,9) = (groebnerMatrix(4,25)/(groebnerMatrix(4,22))-groebnerMatrix(7,27)/(groebnerMatrix(7,25))); groebnerMatrix(12,10) = groebnerMatrix(4,26)/(groebnerMatrix(4,22)); groebnerMatrix(12,11) = groebnerMatrix(4,27)/(groebnerMatrix(4,22)); groebnerMatrix(12,12) = -groebnerMatrix(7,28)/(groebnerMatrix(7,25)); groebnerMatrix(12,13) = -groebnerMatrix(7,29)/(groebnerMatrix(7,25)); groebnerMatrix(12,15) = (groebnerMatrix(4,28)/(groebnerMatrix(4,22))-groebnerMatrix(7,30)/(groebnerMatrix(7,25))); groebnerMatrix(12,16) = groebnerMatrix(4,29)/(groebnerMatrix(4,22)); groebnerMatrix(12,17) = groebnerMatrix(4,30)/(groebnerMatrix(4,22)); groebnerMatrix(12,18) = -groebnerMatrix(7,31)/(groebnerMatrix(7,25)); groebnerMatrix(12,20) = groebnerMatrix(4,31)/(groebnerMatrix(4,22)); groebnerMatrix(12,22) = -groebnerMatrix(7,32)/(groebnerMatrix(7,25)); groebnerMatrix(12,23) = -groebnerMatrix(7,33)/(groebnerMatrix(7,25)); groebnerMatrix(12,25) = (groebnerMatrix(4,32)/(groebnerMatrix(4,22))-groebnerMatrix(7,34)/(groebnerMatrix(7,25))); groebnerMatrix(12,26) = groebnerMatrix(4,33)/(groebnerMatrix(4,22)); groebnerMatrix(12,27) = groebnerMatrix(4,34)/(groebnerMatrix(4,22)); groebnerMatrix(12,28) = -groebnerMatrix(7,35)/(groebnerMatrix(7,25)); groebnerMatrix(12,30) = groebnerMatrix(4,35)/(groebnerMatrix(4,22)); groebnerMatrix(12,32) = -groebnerMatrix(7,36)/(groebnerMatrix(7,25)); groebnerMatrix(12,34) = groebnerMatrix(4,36)/(groebnerMatrix(4,22)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial13( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(13,5) = groebnerMatrix(5,24)/(groebnerMatrix(5,23)); groebnerMatrix(13,6) = -groebnerMatrix(6,25)/(groebnerMatrix(6,24)); groebnerMatrix(13,7) = (groebnerMatrix(5,25)/(groebnerMatrix(5,23))-groebnerMatrix(6,26)/(groebnerMatrix(6,24))); groebnerMatrix(13,8) = groebnerMatrix(5,26)/(groebnerMatrix(5,23)); groebnerMatrix(13,9) = -groebnerMatrix(6,27)/(groebnerMatrix(6,24)); groebnerMatrix(13,10) = groebnerMatrix(5,27)/(groebnerMatrix(5,23)); groebnerMatrix(13,12) = -groebnerMatrix(6,28)/(groebnerMatrix(6,24)); groebnerMatrix(13,13) = (groebnerMatrix(5,28)/(groebnerMatrix(5,23))-groebnerMatrix(6,29)/(groebnerMatrix(6,24))); groebnerMatrix(13,14) = groebnerMatrix(5,29)/(groebnerMatrix(5,23)); groebnerMatrix(13,15) = -groebnerMatrix(6,30)/(groebnerMatrix(6,24)); groebnerMatrix(13,16) = groebnerMatrix(5,30)/(groebnerMatrix(5,23)); groebnerMatrix(13,18) = -groebnerMatrix(6,31)/(groebnerMatrix(6,24)); groebnerMatrix(13,19) = groebnerMatrix(5,31)/(groebnerMatrix(5,23)); groebnerMatrix(13,22) = -groebnerMatrix(6,32)/(groebnerMatrix(6,24)); groebnerMatrix(13,23) = (groebnerMatrix(5,32)/(groebnerMatrix(5,23))-groebnerMatrix(6,33)/(groebnerMatrix(6,24))); groebnerMatrix(13,24) = groebnerMatrix(5,33)/(groebnerMatrix(5,23)); groebnerMatrix(13,25) = -groebnerMatrix(6,34)/(groebnerMatrix(6,24)); groebnerMatrix(13,26) = groebnerMatrix(5,34)/(groebnerMatrix(5,23)); groebnerMatrix(13,28) = -groebnerMatrix(6,35)/(groebnerMatrix(6,24)); groebnerMatrix(13,29) = groebnerMatrix(5,35)/(groebnerMatrix(5,23)); groebnerMatrix(13,32) = -groebnerMatrix(6,36)/(groebnerMatrix(6,24)); groebnerMatrix(13,33) = groebnerMatrix(5,36)/(groebnerMatrix(5,23)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial14( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(14,4) = (groebnerMatrix(4,23)/(groebnerMatrix(4,22))-groebnerMatrix(5,24)/(groebnerMatrix(5,23))); groebnerMatrix(14,5) = groebnerMatrix(4,24)/(groebnerMatrix(4,22)); groebnerMatrix(14,6) = -groebnerMatrix(5,25)/(groebnerMatrix(5,23)); groebnerMatrix(14,7) = (groebnerMatrix(4,25)/(groebnerMatrix(4,22))-groebnerMatrix(5,26)/(groebnerMatrix(5,23))); groebnerMatrix(14,8) = groebnerMatrix(4,26)/(groebnerMatrix(4,22)); groebnerMatrix(14,9) = -groebnerMatrix(5,27)/(groebnerMatrix(5,23)); groebnerMatrix(14,10) = groebnerMatrix(4,27)/(groebnerMatrix(4,22)); groebnerMatrix(14,12) = -groebnerMatrix(5,28)/(groebnerMatrix(5,23)); groebnerMatrix(14,13) = (groebnerMatrix(4,28)/(groebnerMatrix(4,22))-groebnerMatrix(5,29)/(groebnerMatrix(5,23))); groebnerMatrix(14,14) = groebnerMatrix(4,29)/(groebnerMatrix(4,22)); groebnerMatrix(14,15) = -groebnerMatrix(5,30)/(groebnerMatrix(5,23)); groebnerMatrix(14,16) = groebnerMatrix(4,30)/(groebnerMatrix(4,22)); groebnerMatrix(14,18) = -groebnerMatrix(5,31)/(groebnerMatrix(5,23)); groebnerMatrix(14,19) = groebnerMatrix(4,31)/(groebnerMatrix(4,22)); groebnerMatrix(14,22) = -groebnerMatrix(5,32)/(groebnerMatrix(5,23)); groebnerMatrix(14,23) = (groebnerMatrix(4,32)/(groebnerMatrix(4,22))-groebnerMatrix(5,33)/(groebnerMatrix(5,23))); groebnerMatrix(14,24) = groebnerMatrix(4,33)/(groebnerMatrix(4,22)); groebnerMatrix(14,25) = -groebnerMatrix(5,34)/(groebnerMatrix(5,23)); groebnerMatrix(14,26) = groebnerMatrix(4,34)/(groebnerMatrix(4,22)); groebnerMatrix(14,28) = -groebnerMatrix(5,35)/(groebnerMatrix(5,23)); groebnerMatrix(14,29) = groebnerMatrix(4,35)/(groebnerMatrix(4,22)); groebnerMatrix(14,32) = -groebnerMatrix(5,36)/(groebnerMatrix(5,23)); groebnerMatrix(14,33) = groebnerMatrix(4,36)/(groebnerMatrix(4,22)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial15( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(15,3) = groebnerMatrix(13,21)/(groebnerMatrix(13,20)); groebnerMatrix(15,11) = -groebnerMatrix(14,27)/(groebnerMatrix(14,21)); groebnerMatrix(15,15) = -groebnerMatrix(14,28)/(groebnerMatrix(14,21)); groebnerMatrix(15,16) = -groebnerMatrix(14,29)/(groebnerMatrix(14,21)); groebnerMatrix(15,17) = (groebnerMatrix(13,27)/(groebnerMatrix(13,20))-groebnerMatrix(14,30)/(groebnerMatrix(14,21))); groebnerMatrix(15,18) = groebnerMatrix(13,28)/(groebnerMatrix(13,20)); groebnerMatrix(15,19) = groebnerMatrix(13,29)/(groebnerMatrix(13,20)); groebnerMatrix(15,20) = (groebnerMatrix(13,30)/(groebnerMatrix(13,20))-groebnerMatrix(14,31)/(groebnerMatrix(14,21))); groebnerMatrix(15,21) = groebnerMatrix(13,31)/(groebnerMatrix(13,20)); groebnerMatrix(15,25) = -groebnerMatrix(14,32)/(groebnerMatrix(14,21)); groebnerMatrix(15,26) = -groebnerMatrix(14,33)/(groebnerMatrix(14,21)); groebnerMatrix(15,27) = -groebnerMatrix(14,34)/(groebnerMatrix(14,21)); groebnerMatrix(15,28) = groebnerMatrix(13,32)/(groebnerMatrix(13,20)); groebnerMatrix(15,29) = groebnerMatrix(13,33)/(groebnerMatrix(13,20)); groebnerMatrix(15,30) = (groebnerMatrix(13,34)/(groebnerMatrix(13,20))-groebnerMatrix(14,35)/(groebnerMatrix(14,21))); groebnerMatrix(15,31) = groebnerMatrix(13,35)/(groebnerMatrix(13,20)); groebnerMatrix(15,34) = -groebnerMatrix(14,36)/(groebnerMatrix(14,21)); groebnerMatrix(15,35) = groebnerMatrix(13,36)/(groebnerMatrix(13,20)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial16( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(16,2) = groebnerMatrix(12,20)/(groebnerMatrix(12,19)); groebnerMatrix(16,3) = groebnerMatrix(12,21)/(groebnerMatrix(12,19)); groebnerMatrix(16,10) = -groebnerMatrix(14,27)/(groebnerMatrix(14,21)); groebnerMatrix(16,13) = -groebnerMatrix(14,28)/(groebnerMatrix(14,21)); groebnerMatrix(16,14) = -groebnerMatrix(14,29)/(groebnerMatrix(14,21)); groebnerMatrix(16,16) = -groebnerMatrix(14,30)/(groebnerMatrix(14,21)); groebnerMatrix(16,17) = groebnerMatrix(12,27)/(groebnerMatrix(12,19)); groebnerMatrix(16,18) = groebnerMatrix(12,28)/(groebnerMatrix(12,19)); groebnerMatrix(16,19) = (groebnerMatrix(12,29)/(groebnerMatrix(12,19))-groebnerMatrix(14,31)/(groebnerMatrix(14,21))); groebnerMatrix(16,20) = groebnerMatrix(12,30)/(groebnerMatrix(12,19)); groebnerMatrix(16,21) = groebnerMatrix(12,31)/(groebnerMatrix(12,19)); groebnerMatrix(16,23) = -groebnerMatrix(14,32)/(groebnerMatrix(14,21)); groebnerMatrix(16,24) = -groebnerMatrix(14,33)/(groebnerMatrix(14,21)); groebnerMatrix(16,26) = -groebnerMatrix(14,34)/(groebnerMatrix(14,21)); groebnerMatrix(16,28) = groebnerMatrix(12,32)/(groebnerMatrix(12,19)); groebnerMatrix(16,29) = (groebnerMatrix(12,33)/(groebnerMatrix(12,19))-groebnerMatrix(14,35)/(groebnerMatrix(14,21))); groebnerMatrix(16,30) = groebnerMatrix(12,34)/(groebnerMatrix(12,19)); groebnerMatrix(16,31) = groebnerMatrix(12,35)/(groebnerMatrix(12,19)); groebnerMatrix(16,33) = -groebnerMatrix(14,36)/(groebnerMatrix(14,21)); groebnerMatrix(16,35) = groebnerMatrix(12,36)/(groebnerMatrix(12,19)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial17( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(17,1) = groebnerMatrix(11,19)/(groebnerMatrix(11,18)); groebnerMatrix(17,2) = groebnerMatrix(11,20)/(groebnerMatrix(11,18)); groebnerMatrix(17,3) = groebnerMatrix(11,21)/(groebnerMatrix(11,18)); groebnerMatrix(17,9) = -groebnerMatrix(14,27)/(groebnerMatrix(14,21)); groebnerMatrix(17,12) = -groebnerMatrix(14,28)/(groebnerMatrix(14,21)); groebnerMatrix(17,13) = -groebnerMatrix(14,29)/(groebnerMatrix(14,21)); groebnerMatrix(17,15) = -groebnerMatrix(14,30)/(groebnerMatrix(14,21)); groebnerMatrix(17,17) = groebnerMatrix(11,27)/(groebnerMatrix(11,18)); groebnerMatrix(17,18) = (groebnerMatrix(11,28)/(groebnerMatrix(11,18))-groebnerMatrix(14,31)/(groebnerMatrix(14,21))); groebnerMatrix(17,19) = groebnerMatrix(11,29)/(groebnerMatrix(11,18)); groebnerMatrix(17,20) = groebnerMatrix(11,30)/(groebnerMatrix(11,18)); groebnerMatrix(17,21) = groebnerMatrix(11,31)/(groebnerMatrix(11,18)); groebnerMatrix(17,22) = -groebnerMatrix(14,32)/(groebnerMatrix(14,21)); groebnerMatrix(17,23) = -groebnerMatrix(14,33)/(groebnerMatrix(14,21)); groebnerMatrix(17,25) = -groebnerMatrix(14,34)/(groebnerMatrix(14,21)); groebnerMatrix(17,28) = (groebnerMatrix(11,32)/(groebnerMatrix(11,18))-groebnerMatrix(14,35)/(groebnerMatrix(14,21))); groebnerMatrix(17,29) = groebnerMatrix(11,33)/(groebnerMatrix(11,18)); groebnerMatrix(17,30) = groebnerMatrix(11,34)/(groebnerMatrix(11,18)); groebnerMatrix(17,31) = groebnerMatrix(11,35)/(groebnerMatrix(11,18)); groebnerMatrix(17,32) = -groebnerMatrix(14,36)/(groebnerMatrix(14,21)); groebnerMatrix(17,35) = groebnerMatrix(11,36)/(groebnerMatrix(11,18)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial18( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(18,0) = groebnerMatrix(10,18)/(groebnerMatrix(10,17)); groebnerMatrix(18,1) = groebnerMatrix(10,19)/(groebnerMatrix(10,17)); groebnerMatrix(18,2) = (groebnerMatrix(10,20)/(groebnerMatrix(10,17))-groebnerMatrix(13,21)/(groebnerMatrix(13,20))); groebnerMatrix(18,3) = groebnerMatrix(10,21)/(groebnerMatrix(10,17)); groebnerMatrix(18,11) = -groebnerMatrix(13,27)/(groebnerMatrix(13,20)); groebnerMatrix(18,15) = -groebnerMatrix(13,28)/(groebnerMatrix(13,20)); groebnerMatrix(18,16) = -groebnerMatrix(13,29)/(groebnerMatrix(13,20)); groebnerMatrix(18,17) = (groebnerMatrix(10,27)/(groebnerMatrix(10,17))-groebnerMatrix(13,30)/(groebnerMatrix(13,20))); groebnerMatrix(18,18) = groebnerMatrix(10,28)/(groebnerMatrix(10,17)); groebnerMatrix(18,19) = groebnerMatrix(10,29)/(groebnerMatrix(10,17)); groebnerMatrix(18,20) = (groebnerMatrix(10,30)/(groebnerMatrix(10,17))-groebnerMatrix(13,31)/(groebnerMatrix(13,20))); groebnerMatrix(18,21) = groebnerMatrix(10,31)/(groebnerMatrix(10,17)); groebnerMatrix(18,25) = -groebnerMatrix(13,32)/(groebnerMatrix(13,20)); groebnerMatrix(18,26) = -groebnerMatrix(13,33)/(groebnerMatrix(13,20)); groebnerMatrix(18,27) = -groebnerMatrix(13,34)/(groebnerMatrix(13,20)); groebnerMatrix(18,28) = groebnerMatrix(10,32)/(groebnerMatrix(10,17)); groebnerMatrix(18,29) = groebnerMatrix(10,33)/(groebnerMatrix(10,17)); groebnerMatrix(18,30) = (groebnerMatrix(10,34)/(groebnerMatrix(10,17))-groebnerMatrix(13,35)/(groebnerMatrix(13,20))); groebnerMatrix(18,31) = groebnerMatrix(10,35)/(groebnerMatrix(10,17)); groebnerMatrix(18,34) = -groebnerMatrix(13,36)/(groebnerMatrix(13,20)); groebnerMatrix(18,35) = groebnerMatrix(10,36)/(groebnerMatrix(10,17)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial19( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(19,21) = (groebnerMatrix(13,21)/(groebnerMatrix(13,20))-groebnerMatrix(18,31)/(groebnerMatrix(18,30))); groebnerMatrix(19,27) = groebnerMatrix(13,27)/(groebnerMatrix(13,20)); groebnerMatrix(19,28) = (groebnerMatrix(13,28)/(groebnerMatrix(13,20))-groebnerMatrix(18,32)/(groebnerMatrix(18,30))); groebnerMatrix(19,29) = (groebnerMatrix(13,29)/(groebnerMatrix(13,20))-groebnerMatrix(18,33)/(groebnerMatrix(18,30))); groebnerMatrix(19,30) = (groebnerMatrix(13,30)/(groebnerMatrix(13,20))-groebnerMatrix(18,34)/(groebnerMatrix(18,30))); groebnerMatrix(19,31) = (groebnerMatrix(13,31)/(groebnerMatrix(13,20))-groebnerMatrix(18,35)/(groebnerMatrix(18,30))); groebnerMatrix(19,32) = groebnerMatrix(13,32)/(groebnerMatrix(13,20)); groebnerMatrix(19,33) = groebnerMatrix(13,33)/(groebnerMatrix(13,20)); groebnerMatrix(19,34) = groebnerMatrix(13,34)/(groebnerMatrix(13,20)); groebnerMatrix(19,35) = (groebnerMatrix(13,35)/(groebnerMatrix(13,20))-groebnerMatrix(18,36)/(groebnerMatrix(18,30))); groebnerMatrix(19,36) = groebnerMatrix(13,36)/(groebnerMatrix(13,20)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial20( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(20,20) = (groebnerMatrix(12,20)/(groebnerMatrix(12,19))-groebnerMatrix(17,30)/(groebnerMatrix(17,29))); groebnerMatrix(20,21) = (groebnerMatrix(12,21)/(groebnerMatrix(12,19))-groebnerMatrix(17,31)/(groebnerMatrix(17,29))); groebnerMatrix(20,27) = groebnerMatrix(12,27)/(groebnerMatrix(12,19)); groebnerMatrix(20,28) = (groebnerMatrix(12,28)/(groebnerMatrix(12,19))-groebnerMatrix(17,32)/(groebnerMatrix(17,29))); groebnerMatrix(20,29) = (groebnerMatrix(12,29)/(groebnerMatrix(12,19))-groebnerMatrix(17,33)/(groebnerMatrix(17,29))); groebnerMatrix(20,30) = (groebnerMatrix(12,30)/(groebnerMatrix(12,19))-groebnerMatrix(17,34)/(groebnerMatrix(17,29))); groebnerMatrix(20,31) = (groebnerMatrix(12,31)/(groebnerMatrix(12,19))-groebnerMatrix(17,35)/(groebnerMatrix(17,29))); groebnerMatrix(20,32) = groebnerMatrix(12,32)/(groebnerMatrix(12,19)); groebnerMatrix(20,33) = groebnerMatrix(12,33)/(groebnerMatrix(12,19)); groebnerMatrix(20,34) = groebnerMatrix(12,34)/(groebnerMatrix(12,19)); groebnerMatrix(20,35) = (groebnerMatrix(12,35)/(groebnerMatrix(12,19))-groebnerMatrix(17,36)/(groebnerMatrix(17,29))); groebnerMatrix(20,36) = groebnerMatrix(12,36)/(groebnerMatrix(12,19)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial21( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(21,19) = (groebnerMatrix(11,19)/(groebnerMatrix(11,18))-groebnerMatrix(16,29)/(groebnerMatrix(16,28))); groebnerMatrix(21,20) = (groebnerMatrix(11,20)/(groebnerMatrix(11,18))-groebnerMatrix(16,30)/(groebnerMatrix(16,28))); groebnerMatrix(21,21) = (groebnerMatrix(11,21)/(groebnerMatrix(11,18))-groebnerMatrix(16,31)/(groebnerMatrix(16,28))); groebnerMatrix(21,27) = groebnerMatrix(11,27)/(groebnerMatrix(11,18)); groebnerMatrix(21,28) = (groebnerMatrix(11,28)/(groebnerMatrix(11,18))-groebnerMatrix(16,32)/(groebnerMatrix(16,28))); groebnerMatrix(21,29) = (groebnerMatrix(11,29)/(groebnerMatrix(11,18))-groebnerMatrix(16,33)/(groebnerMatrix(16,28))); groebnerMatrix(21,30) = (groebnerMatrix(11,30)/(groebnerMatrix(11,18))-groebnerMatrix(16,34)/(groebnerMatrix(16,28))); groebnerMatrix(21,31) = (groebnerMatrix(11,31)/(groebnerMatrix(11,18))-groebnerMatrix(16,35)/(groebnerMatrix(16,28))); groebnerMatrix(21,32) = groebnerMatrix(11,32)/(groebnerMatrix(11,18)); groebnerMatrix(21,33) = groebnerMatrix(11,33)/(groebnerMatrix(11,18)); groebnerMatrix(21,34) = groebnerMatrix(11,34)/(groebnerMatrix(11,18)); groebnerMatrix(21,35) = (groebnerMatrix(11,35)/(groebnerMatrix(11,18))-groebnerMatrix(16,36)/(groebnerMatrix(16,28))); groebnerMatrix(21,36) = groebnerMatrix(11,36)/(groebnerMatrix(11,18)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial22( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(22,18) = (groebnerMatrix(10,18)/(groebnerMatrix(10,17))-groebnerMatrix(15,28)/(groebnerMatrix(15,27))); groebnerMatrix(22,19) = (groebnerMatrix(10,19)/(groebnerMatrix(10,17))-groebnerMatrix(15,29)/(groebnerMatrix(15,27))); groebnerMatrix(22,20) = (groebnerMatrix(10,20)/(groebnerMatrix(10,17))-groebnerMatrix(15,30)/(groebnerMatrix(15,27))); groebnerMatrix(22,21) = (groebnerMatrix(10,21)/(groebnerMatrix(10,17))-groebnerMatrix(15,31)/(groebnerMatrix(15,27))); groebnerMatrix(22,27) = groebnerMatrix(10,27)/(groebnerMatrix(10,17)); groebnerMatrix(22,28) = (groebnerMatrix(10,28)/(groebnerMatrix(10,17))-groebnerMatrix(15,32)/(groebnerMatrix(15,27))); groebnerMatrix(22,29) = (groebnerMatrix(10,29)/(groebnerMatrix(10,17))-groebnerMatrix(15,33)/(groebnerMatrix(15,27))); groebnerMatrix(22,30) = (groebnerMatrix(10,30)/(groebnerMatrix(10,17))-groebnerMatrix(15,34)/(groebnerMatrix(15,27))); groebnerMatrix(22,31) = (groebnerMatrix(10,31)/(groebnerMatrix(10,17))-groebnerMatrix(15,35)/(groebnerMatrix(15,27))); groebnerMatrix(22,32) = groebnerMatrix(10,32)/(groebnerMatrix(10,17)); groebnerMatrix(22,33) = groebnerMatrix(10,33)/(groebnerMatrix(10,17)); groebnerMatrix(22,34) = groebnerMatrix(10,34)/(groebnerMatrix(10,17)); groebnerMatrix(22,35) = (groebnerMatrix(10,35)/(groebnerMatrix(10,17))-groebnerMatrix(15,36)/(groebnerMatrix(15,27))); groebnerMatrix(22,36) = groebnerMatrix(10,36)/(groebnerMatrix(10,17)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial23( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(23,15) = -groebnerMatrix(15,28)/(groebnerMatrix(15,27)); groebnerMatrix(23,16) = -groebnerMatrix(15,29)/(groebnerMatrix(15,27)); groebnerMatrix(23,17) = (groebnerMatrix(9,17)/(groebnerMatrix(9,11))-groebnerMatrix(15,30)/(groebnerMatrix(15,27))); groebnerMatrix(23,18) = groebnerMatrix(9,18)/(groebnerMatrix(9,11)); groebnerMatrix(23,19) = groebnerMatrix(9,19)/(groebnerMatrix(9,11)); groebnerMatrix(23,20) = (groebnerMatrix(9,20)/(groebnerMatrix(9,11))-groebnerMatrix(15,31)/(groebnerMatrix(15,27))); groebnerMatrix(23,21) = groebnerMatrix(9,21)/(groebnerMatrix(9,11)); groebnerMatrix(23,25) = -groebnerMatrix(15,32)/(groebnerMatrix(15,27)); groebnerMatrix(23,26) = -groebnerMatrix(15,33)/(groebnerMatrix(15,27)); groebnerMatrix(23,27) = (groebnerMatrix(9,27)/(groebnerMatrix(9,11))-groebnerMatrix(15,34)/(groebnerMatrix(15,27))); groebnerMatrix(23,28) = groebnerMatrix(9,28)/(groebnerMatrix(9,11)); groebnerMatrix(23,29) = groebnerMatrix(9,29)/(groebnerMatrix(9,11)); groebnerMatrix(23,30) = (groebnerMatrix(9,30)/(groebnerMatrix(9,11))-groebnerMatrix(15,35)/(groebnerMatrix(15,27))); groebnerMatrix(23,31) = groebnerMatrix(9,31)/(groebnerMatrix(9,11)); groebnerMatrix(23,32) = groebnerMatrix(9,32)/(groebnerMatrix(9,11)); groebnerMatrix(23,33) = groebnerMatrix(9,33)/(groebnerMatrix(9,11)); groebnerMatrix(23,34) = (groebnerMatrix(9,34)/(groebnerMatrix(9,11))-groebnerMatrix(15,36)/(groebnerMatrix(15,27))); groebnerMatrix(23,35) = groebnerMatrix(9,35)/(groebnerMatrix(9,11)); groebnerMatrix(23,36) = groebnerMatrix(9,36)/(groebnerMatrix(9,11)); } void opengv::absolute_pose::modules::gpnp4::sPolynomial24( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(24,32) = groebnerMatrix(19,32)/(groebnerMatrix(19,31)); groebnerMatrix(24,33) = groebnerMatrix(19,33)/(groebnerMatrix(19,31)); groebnerMatrix(24,34) = groebnerMatrix(19,34)/(groebnerMatrix(19,31)); groebnerMatrix(24,35) = (groebnerMatrix(19,35)/(groebnerMatrix(19,31))-groebnerMatrix(23,36)/(groebnerMatrix(23,35))); groebnerMatrix(24,36) = groebnerMatrix(19,36)/(groebnerMatrix(19,31)); } opengv/src/absolute_pose/modules/gpnp4/init.cpp0000664016516101651610000004634713344612246020627 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp4::init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Matrix & m, Eigen::Matrix & k, Eigen::Matrix & l, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ) { Eigen::Vector3d temp = c0-c1; double c01w = temp.norm()*temp.norm(); temp = c0-c2; double c02w = temp.norm()*temp.norm(); temp = c0-c3; double c03w = temp.norm()*temp.norm(); temp = c1-c2; double c12w = temp.norm()*temp.norm(); temp = c1-c3; double c13w = temp.norm()*temp.norm(); groebnerMatrix(0,22) = ((((((((-2*l(0,0)*l(3,0)-2*l(1,0)*l(4,0))-2*l(2,0)*l(5,0))+pow(l(0,0),2))+pow(l(3,0),2))+pow(l(1,0),2))+pow(l(4,0),2))+pow(l(2,0),2))+pow(l(5,0),2)); groebnerMatrix(0,23) = (((((((((((2*k(0,0)*l(0,0)-2*k(0,0)*l(3,0))-2*l(0,0)*k(3,0))+2*k(3,0)*l(3,0))+2*k(1,0)*l(1,0))-2*k(1,0)*l(4,0))-2*l(1,0)*k(4,0))+2*k(4,0)*l(4,0))+2*k(2,0)*l(2,0))-2*k(2,0)*l(5,0))-2*l(2,0)*k(5,0))+2*k(5,0)*l(5,0)); groebnerMatrix(0,24) = ((((((((-2*k(0,0)*k(3,0)-2*k(1,0)*k(4,0))-2*k(2,0)*k(5,0))+pow(k(0,0),2))+pow(k(3,0),2))+pow(k(1,0),2))+pow(k(4,0),2))+pow(k(2,0),2))+pow(k(5,0),2)); groebnerMatrix(0,25) = (((((((((((2*m(2,0)*l(2,0)+2*m(0,0)*l(0,0))-2*m(0,0)*l(3,0))-2*l(0,0)*m(3,0))+2*m(3,0)*l(3,0))+2*m(1,0)*l(1,0))-2*m(1,0)*l(4,0))-2*l(1,0)*m(4,0))+2*m(4,0)*l(4,0))-2*m(2,0)*l(5,0))-2*l(2,0)*m(5,0))+2*m(5,0)*l(5,0)); groebnerMatrix(0,26) = (((((((((((2*m(2,0)*k(2,0)+2*m(0,0)*k(0,0))-2*m(0,0)*k(3,0))-2*k(0,0)*m(3,0))+2*m(3,0)*k(3,0))+2*m(1,0)*k(1,0))-2*m(1,0)*k(4,0))-2*k(1,0)*m(4,0))+2*m(4,0)*k(4,0))-2*m(2,0)*k(5,0))-2*k(2,0)*m(5,0))+2*m(5,0)*k(5,0)); groebnerMatrix(0,27) = ((((((((-2*m(0,0)*m(3,0)-2*m(1,0)*m(4,0))-2*m(2,0)*m(5,0))+pow(m(0,0),2))+pow(m(3,0),2))+pow(m(1,0),2))+pow(m(4,0),2))+pow(m(2,0),2))+pow(m(5,0),2)); groebnerMatrix(0,28) = (((((((((((2*n(0,0)*l(0,0)-2*n(0,0)*l(3,0))-2*l(0,0)*n(3,0))+2*n(3,0)*l(3,0))+2*n(1,0)*l(1,0))-2*n(1,0)*l(4,0))-2*l(1,0)*n(4,0))+2*n(4,0)*l(4,0))+2*n(2,0)*l(2,0))-2*n(2,0)*l(5,0))-2*l(2,0)*n(5,0))+2*n(5,0)*l(5,0)); groebnerMatrix(0,29) = (((((((((((2*n(0,0)*k(0,0)-2*n(0,0)*k(3,0))-2*k(0,0)*n(3,0))+2*n(3,0)*k(3,0))+2*n(1,0)*k(1,0))-2*n(1,0)*k(4,0))-2*k(1,0)*n(4,0))+2*n(4,0)*k(4,0))+2*n(2,0)*k(2,0))-2*n(2,0)*k(5,0))-2*k(2,0)*n(5,0))+2*n(5,0)*k(5,0)); groebnerMatrix(0,30) = (((((((((((2*n(0,0)*m(0,0)-2*n(0,0)*m(3,0))-2*m(0,0)*n(3,0))+2*n(3,0)*m(3,0))+2*n(1,0)*m(1,0))-2*n(1,0)*m(4,0))-2*m(1,0)*n(4,0))+2*n(4,0)*m(4,0))+2*n(2,0)*m(2,0))-2*n(2,0)*m(5,0))-2*m(2,0)*n(5,0))+2*n(5,0)*m(5,0)); groebnerMatrix(0,31) = ((((((((-2*n(0,0)*n(3,0)-2*n(1,0)*n(4,0))-2*n(2,0)*n(5,0))+pow(n(0,0),2))+pow(n(3,0),2))+pow(n(1,0),2))+pow(n(4,0),2))+pow(n(2,0),2))+pow(n(5,0),2)); groebnerMatrix(0,32) = (((((((((((2*a(0,0)*l(0,0)-2*a(0,0)*l(3,0))-2*l(0,0)*a(3,0))+2*a(3,0)*l(3,0))+2*a(1,0)*l(1,0))-2*a(1,0)*l(4,0))-2*l(1,0)*a(4,0))+2*a(4,0)*l(4,0))+2*a(2,0)*l(2,0))-2*a(2,0)*l(5,0))-2*l(2,0)*a(5,0))+2*a(5,0)*l(5,0)); groebnerMatrix(0,33) = (((((((((((2*a(0,0)*k(0,0)-2*a(0,0)*k(3,0))-2*k(0,0)*a(3,0))+2*a(3,0)*k(3,0))+2*a(1,0)*k(1,0))-2*a(1,0)*k(4,0))-2*k(1,0)*a(4,0))+2*a(4,0)*k(4,0))+2*a(2,0)*k(2,0))-2*a(2,0)*k(5,0))-2*k(2,0)*a(5,0))+2*a(5,0)*k(5,0)); groebnerMatrix(0,34) = (((((((((((2*a(0,0)*m(0,0)-2*a(0,0)*m(3,0))-2*m(0,0)*a(3,0))+2*a(3,0)*m(3,0))+2*a(1,0)*m(1,0))-2*a(1,0)*m(4,0))-2*m(1,0)*a(4,0))+2*a(4,0)*m(4,0))+2*a(2,0)*m(2,0))-2*a(2,0)*m(5,0))-2*m(2,0)*a(5,0))+2*a(5,0)*m(5,0)); groebnerMatrix(0,35) = (((((((((((2*a(0,0)*n(0,0)-2*a(0,0)*n(3,0))-2*n(0,0)*a(3,0))+2*a(3,0)*n(3,0))+2*a(1,0)*n(1,0))-2*a(1,0)*n(4,0))-2*n(1,0)*a(4,0))+2*a(4,0)*n(4,0))+2*a(2,0)*n(2,0))-2*a(2,0)*n(5,0))-2*n(2,0)*a(5,0))+2*a(5,0)*n(5,0)); groebnerMatrix(0,36) = (((((((((-c01w+pow(a(0,0),2))-2*a(0,0)*a(3,0))+pow(a(3,0),2))+pow(a(1,0),2))-2*a(1,0)*a(4,0))+pow(a(4,0),2))+pow(a(2,0),2))-2*a(2,0)*a(5,0))+pow(a(5,0),2)); groebnerMatrix(1,22) = ((((((((-2*l(0,0)*l(6,0)-2*l(1,0)*l(7,0))-2*l(2,0)*l(8,0))+pow(l(0,0),2))+pow(l(1,0),2))+pow(l(2,0),2))+pow(l(6,0),2))+pow(l(7,0),2))+pow(l(8,0),2)); groebnerMatrix(1,23) = (((((((((((2*k(0,0)*l(0,0)+2*k(1,0)*l(1,0))+2*k(2,0)*l(2,0))-2*k(0,0)*l(6,0))-2*l(0,0)*k(6,0))+2*k(6,0)*l(6,0))-2*k(1,0)*l(7,0))-2*l(1,0)*k(7,0))+2*k(7,0)*l(7,0))-2*k(2,0)*l(8,0))-2*l(2,0)*k(8,0))+2*k(8,0)*l(8,0)); groebnerMatrix(1,24) = ((((((((-2*k(0,0)*k(6,0)-2*k(1,0)*k(7,0))-2*k(2,0)*k(8,0))+pow(k(0,0),2))+pow(k(1,0),2))+pow(k(2,0),2))+pow(k(6,0),2))+pow(k(7,0),2))+pow(k(8,0),2)); groebnerMatrix(1,25) = (((((((((((2*m(2,0)*l(2,0)+2*m(0,0)*l(0,0))+2*m(1,0)*l(1,0))-2*m(0,0)*l(6,0))-2*l(0,0)*m(6,0))+2*m(6,0)*l(6,0))-2*m(1,0)*l(7,0))-2*l(1,0)*m(7,0))+2*m(7,0)*l(7,0))-2*m(2,0)*l(8,0))-2*l(2,0)*m(8,0))+2*m(8,0)*l(8,0)); groebnerMatrix(1,26) = (((((((((((2*m(2,0)*k(2,0)+2*m(0,0)*k(0,0))+2*m(1,0)*k(1,0))-2*m(0,0)*k(6,0))-2*k(0,0)*m(6,0))+2*m(6,0)*k(6,0))-2*m(1,0)*k(7,0))-2*k(1,0)*m(7,0))+2*m(7,0)*k(7,0))-2*m(2,0)*k(8,0))-2*k(2,0)*m(8,0))+2*m(8,0)*k(8,0)); groebnerMatrix(1,27) = ((((((((-2*m(0,0)*m(6,0)-2*m(1,0)*m(7,0))-2*m(2,0)*m(8,0))+pow(m(0,0),2))+pow(m(1,0),2))+pow(m(2,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2)); groebnerMatrix(1,28) = (((((((((((2*n(0,0)*l(0,0)+2*n(1,0)*l(1,0))+2*n(2,0)*l(2,0))-2*n(0,0)*l(6,0))-2*l(0,0)*n(6,0))+2*n(6,0)*l(6,0))-2*n(1,0)*l(7,0))-2*l(1,0)*n(7,0))+2*n(7,0)*l(7,0))-2*n(2,0)*l(8,0))-2*l(2,0)*n(8,0))+2*n(8,0)*l(8,0)); groebnerMatrix(1,29) = (((((((((((2*n(0,0)*k(0,0)+2*n(1,0)*k(1,0))+2*n(2,0)*k(2,0))-2*n(0,0)*k(6,0))-2*k(0,0)*n(6,0))+2*n(6,0)*k(6,0))-2*n(1,0)*k(7,0))-2*k(1,0)*n(7,0))+2*n(7,0)*k(7,0))-2*n(2,0)*k(8,0))-2*k(2,0)*n(8,0))+2*n(8,0)*k(8,0)); groebnerMatrix(1,30) = (((((((((((2*n(0,0)*m(0,0)+2*n(1,0)*m(1,0))+2*n(2,0)*m(2,0))-2*n(0,0)*m(6,0))-2*m(0,0)*n(6,0))+2*n(6,0)*m(6,0))-2*n(1,0)*m(7,0))-2*m(1,0)*n(7,0))+2*n(7,0)*m(7,0))-2*n(2,0)*m(8,0))-2*m(2,0)*n(8,0))+2*n(8,0)*m(8,0)); groebnerMatrix(1,31) = ((((((((-2*n(0,0)*n(6,0)-2*n(1,0)*n(7,0))-2*n(2,0)*n(8,0))+pow(n(0,0),2))+pow(n(1,0),2))+pow(n(2,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2)); groebnerMatrix(1,32) = (((((((((((-2*a(0,0)*l(6,0)+2*a(0,0)*l(0,0))+2*a(1,0)*l(1,0))+2*a(2,0)*l(2,0))-2*l(0,0)*a(6,0))+2*a(6,0)*l(6,0))-2*a(1,0)*l(7,0))-2*l(1,0)*a(7,0))+2*a(7,0)*l(7,0))-2*a(2,0)*l(8,0))-2*l(2,0)*a(8,0))+2*a(8,0)*l(8,0)); groebnerMatrix(1,33) = (((((((((((-2*a(0,0)*k(6,0)+2*a(0,0)*k(0,0))+2*a(1,0)*k(1,0))+2*a(2,0)*k(2,0))-2*k(0,0)*a(6,0))+2*a(6,0)*k(6,0))-2*a(1,0)*k(7,0))-2*k(1,0)*a(7,0))+2*a(7,0)*k(7,0))-2*a(2,0)*k(8,0))-2*k(2,0)*a(8,0))+2*a(8,0)*k(8,0)); groebnerMatrix(1,34) = (((((((((((-2*a(0,0)*m(6,0)-2*m(0,0)*a(6,0))+2*a(0,0)*m(0,0))+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))+2*a(6,0)*m(6,0))-2*a(1,0)*m(7,0))-2*m(1,0)*a(7,0))+2*a(7,0)*m(7,0))-2*a(2,0)*m(8,0))-2*m(2,0)*a(8,0))+2*a(8,0)*m(8,0)); groebnerMatrix(1,35) = (((((((((((-2*a(0,0)*n(6,0)-2*n(0,0)*a(6,0))+2*a(0,0)*n(0,0))+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))+2*a(6,0)*n(6,0))-2*a(1,0)*n(7,0))-2*n(1,0)*a(7,0))+2*a(7,0)*n(7,0))-2*a(2,0)*n(8,0))-2*n(2,0)*a(8,0))+2*a(8,0)*n(8,0)); groebnerMatrix(1,36) = (((((((((-c02w+pow(a(0,0),2))+pow(a(1,0),2))+pow(a(2,0),2))-2*a(0,0)*a(6,0))+pow(a(6,0),2))-2*a(1,0)*a(7,0))+pow(a(7,0),2))-2*a(2,0)*a(8,0))+pow(a(8,0),2)); groebnerMatrix(2,22) = ((((((((pow(l(0,0),2)+pow(l(1,0),2))+pow(l(2,0),2))-2*l(0,0)*l(9,0))-2*l(1,0)*l(10,0))-2*l(2,0)*l(11,0))+pow(l(9,0),2))+pow(l(10,0),2))+pow(l(11,0),2)); groebnerMatrix(2,23) = (((((((((((2*k(0,0)*l(0,0)+2*k(1,0)*l(1,0))+2*k(2,0)*l(2,0))-2*k(0,0)*l(9,0))-2*l(0,0)*k(9,0))+2*k(9,0)*l(9,0))-2*k(1,0)*l(10,0))-2*l(1,0)*k(10,0))+2*k(10,0)*l(10,0))-2*k(2,0)*l(11,0))-2*l(2,0)*k(11,0))+2*k(11,0)*l(11,0)); groebnerMatrix(2,24) = ((((((((pow(k(0,0),2)+pow(k(1,0),2))+pow(k(2,0),2))-2*k(0,0)*k(9,0))-2*k(1,0)*k(10,0))-2*k(2,0)*k(11,0))+pow(k(9,0),2))+pow(k(10,0),2))+pow(k(11,0),2)); groebnerMatrix(2,25) = (((((((((((2*m(2,0)*l(2,0)+2*m(0,0)*l(0,0))+2*m(1,0)*l(1,0))-2*m(0,0)*l(9,0))-2*l(0,0)*m(9,0))+2*m(9,0)*l(9,0))-2*m(1,0)*l(10,0))-2*l(1,0)*m(10,0))+2*m(10,0)*l(10,0))-2*m(2,0)*l(11,0))-2*l(2,0)*m(11,0))+2*m(11,0)*l(11,0)); groebnerMatrix(2,26) = (((((((((((2*m(2,0)*k(2,0)+2*m(0,0)*k(0,0))+2*m(1,0)*k(1,0))-2*m(0,0)*k(9,0))-2*k(0,0)*m(9,0))+2*m(9,0)*k(9,0))-2*m(1,0)*k(10,0))-2*k(1,0)*m(10,0))+2*m(10,0)*k(10,0))-2*m(2,0)*k(11,0))-2*k(2,0)*m(11,0))+2*m(11,0)*k(11,0)); groebnerMatrix(2,27) = ((((((((pow(m(0,0),2)+pow(m(1,0),2))+pow(m(2,0),2))-2*m(0,0)*m(9,0))-2*m(1,0)*m(10,0))-2*m(2,0)*m(11,0))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2)); groebnerMatrix(2,28) = (((((((((((2*n(0,0)*l(0,0)+2*n(1,0)*l(1,0))+2*n(2,0)*l(2,0))-2*n(0,0)*l(9,0))-2*l(0,0)*n(9,0))+2*n(9,0)*l(9,0))-2*n(1,0)*l(10,0))-2*l(1,0)*n(10,0))+2*n(10,0)*l(10,0))-2*n(2,0)*l(11,0))-2*l(2,0)*n(11,0))+2*n(11,0)*l(11,0)); groebnerMatrix(2,29) = (((((((((((2*n(0,0)*k(0,0)+2*n(1,0)*k(1,0))+2*n(2,0)*k(2,0))-2*n(0,0)*k(9,0))-2*k(0,0)*n(9,0))+2*n(9,0)*k(9,0))-2*n(1,0)*k(10,0))-2*k(1,0)*n(10,0))+2*n(10,0)*k(10,0))-2*n(2,0)*k(11,0))-2*k(2,0)*n(11,0))+2*n(11,0)*k(11,0)); groebnerMatrix(2,30) = (((((((((((2*n(0,0)*m(0,0)+2*n(1,0)*m(1,0))+2*n(2,0)*m(2,0))-2*n(0,0)*m(9,0))-2*m(0,0)*n(9,0))+2*n(9,0)*m(9,0))-2*n(1,0)*m(10,0))-2*m(1,0)*n(10,0))+2*n(10,0)*m(10,0))-2*n(2,0)*m(11,0))-2*m(2,0)*n(11,0))+2*n(11,0)*m(11,0)); groebnerMatrix(2,31) = ((((((((pow(n(0,0),2)+pow(n(1,0),2))+pow(n(2,0),2))-2*n(0,0)*n(9,0))-2*n(1,0)*n(10,0))-2*n(2,0)*n(11,0))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2)); groebnerMatrix(2,32) = (((((((((((2*a(0,0)*l(0,0)+2*a(1,0)*l(1,0))+2*a(2,0)*l(2,0))-2*a(0,0)*l(9,0))-2*l(0,0)*a(9,0))+2*a(9,0)*l(9,0))-2*a(1,0)*l(10,0))-2*l(1,0)*a(10,0))+2*a(10,0)*l(10,0))-2*a(2,0)*l(11,0))-2*l(2,0)*a(11,0))+2*a(11,0)*l(11,0)); groebnerMatrix(2,33) = (((((((((((2*a(0,0)*k(0,0)+2*a(1,0)*k(1,0))+2*a(2,0)*k(2,0))-2*a(0,0)*k(9,0))-2*k(0,0)*a(9,0))+2*a(9,0)*k(9,0))-2*a(1,0)*k(10,0))-2*k(1,0)*a(10,0))+2*a(10,0)*k(10,0))-2*a(2,0)*k(11,0))-2*k(2,0)*a(11,0))+2*a(11,0)*k(11,0)); groebnerMatrix(2,34) = (((((((((((2*a(0,0)*m(0,0)+2*a(1,0)*m(1,0))+2*a(2,0)*m(2,0))-2*a(0,0)*m(9,0))-2*m(0,0)*a(9,0))+2*a(9,0)*m(9,0))-2*a(1,0)*m(10,0))-2*m(1,0)*a(10,0))+2*a(10,0)*m(10,0))-2*a(2,0)*m(11,0))-2*m(2,0)*a(11,0))+2*a(11,0)*m(11,0)); groebnerMatrix(2,35) = (((((((((((2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0))+2*a(2,0)*n(2,0))-2*a(0,0)*n(9,0))-2*n(0,0)*a(9,0))+2*a(9,0)*n(9,0))-2*a(1,0)*n(10,0))-2*n(1,0)*a(10,0))+2*a(10,0)*n(10,0))-2*a(2,0)*n(11,0))-2*n(2,0)*a(11,0))+2*a(11,0)*n(11,0)); groebnerMatrix(2,36) = (((((((((-c03w+pow(a(0,0),2))+pow(a(1,0),2))+pow(a(2,0),2))-2*a(0,0)*a(9,0))+pow(a(9,0),2))-2*a(1,0)*a(10,0))+pow(a(10,0),2))-2*a(2,0)*a(11,0))+pow(a(11,0),2)); groebnerMatrix(3,22) = ((((((((pow(l(3,0),2)+pow(l(4,0),2))+pow(l(5,0),2))+pow(l(6,0),2))+pow(l(7,0),2))+pow(l(8,0),2))-2*l(3,0)*l(6,0))-2*l(4,0)*l(7,0))-2*l(5,0)*l(8,0)); groebnerMatrix(3,23) = (((((((((((2*k(3,0)*l(3,0)+2*k(4,0)*l(4,0))-2*k(4,0)*l(7,0))-2*l(4,0)*k(7,0))+2*k(5,0)*l(5,0))+2*k(6,0)*l(6,0))+2*k(7,0)*l(7,0))+2*k(8,0)*l(8,0))-2*k(3,0)*l(6,0))-2*l(3,0)*k(6,0))-2*k(5,0)*l(8,0))-2*l(5,0)*k(8,0)); groebnerMatrix(3,24) = ((((((((pow(k(3,0),2)+pow(k(4,0),2))+pow(k(5,0),2))+pow(k(6,0),2))+pow(k(7,0),2))+pow(k(8,0),2))-2*k(3,0)*k(6,0))-2*k(4,0)*k(7,0))-2*k(5,0)*k(8,0)); groebnerMatrix(3,25) = (((((((((((2*m(3,0)*l(3,0)+2*m(4,0)*l(4,0))-2*m(4,0)*l(7,0))-2*l(4,0)*m(7,0))+2*m(5,0)*l(5,0))+2*m(6,0)*l(6,0))+2*m(7,0)*l(7,0))+2*m(8,0)*l(8,0))-2*m(3,0)*l(6,0))-2*l(3,0)*m(6,0))-2*m(5,0)*l(8,0))-2*l(5,0)*m(8,0)); groebnerMatrix(3,26) = (((((((((((2*m(3,0)*k(3,0)+2*m(4,0)*k(4,0))-2*m(4,0)*k(7,0))-2*k(4,0)*m(7,0))+2*m(5,0)*k(5,0))+2*m(6,0)*k(6,0))+2*m(7,0)*k(7,0))+2*m(8,0)*k(8,0))-2*m(3,0)*k(6,0))-2*k(3,0)*m(6,0))-2*m(5,0)*k(8,0))-2*k(5,0)*m(8,0)); groebnerMatrix(3,27) = ((((((((pow(m(3,0),2)+pow(m(4,0),2))+pow(m(5,0),2))+pow(m(6,0),2))+pow(m(7,0),2))+pow(m(8,0),2))-2*m(3,0)*m(6,0))-2*m(4,0)*m(7,0))-2*m(5,0)*m(8,0)); groebnerMatrix(3,28) = (((((((((((2*n(3,0)*l(3,0)+2*n(4,0)*l(4,0))-2*l(4,0)*n(7,0))+2*n(5,0)*l(5,0))+2*n(6,0)*l(6,0))+2*n(7,0)*l(7,0))+2*n(8,0)*l(8,0))-2*n(3,0)*l(6,0))-2*l(3,0)*n(6,0))-2*n(4,0)*l(7,0))-2*n(5,0)*l(8,0))-2*l(5,0)*n(8,0)); groebnerMatrix(3,29) = (((((((((((2*n(3,0)*k(3,0)+2*n(4,0)*k(4,0))-2*k(4,0)*n(7,0))+2*n(5,0)*k(5,0))+2*n(6,0)*k(6,0))+2*n(7,0)*k(7,0))+2*n(8,0)*k(8,0))-2*n(3,0)*k(6,0))-2*k(3,0)*n(6,0))-2*n(4,0)*k(7,0))-2*n(5,0)*k(8,0))-2*k(5,0)*n(8,0)); groebnerMatrix(3,30) = (((((((((((2*n(3,0)*m(3,0)+2*n(4,0)*m(4,0))-2*m(4,0)*n(7,0))+2*n(5,0)*m(5,0))+2*n(6,0)*m(6,0))+2*n(7,0)*m(7,0))+2*n(8,0)*m(8,0))-2*n(3,0)*m(6,0))-2*m(3,0)*n(6,0))-2*n(4,0)*m(7,0))-2*n(5,0)*m(8,0))-2*m(5,0)*n(8,0)); groebnerMatrix(3,31) = ((((((((-2*n(3,0)*n(6,0)+pow(n(3,0),2))+pow(n(4,0),2))+pow(n(5,0),2))+pow(n(6,0),2))+pow(n(7,0),2))+pow(n(8,0),2))-2*n(4,0)*n(7,0))-2*n(5,0)*n(8,0)); groebnerMatrix(3,32) = (((((((((((-2*a(3,0)*l(6,0)+2*a(3,0)*l(3,0))+2*a(4,0)*l(4,0))+2*a(5,0)*l(5,0))+2*a(6,0)*l(6,0))+2*a(7,0)*l(7,0))+2*a(8,0)*l(8,0))-2*l(3,0)*a(6,0))-2*a(4,0)*l(7,0))-2*l(4,0)*a(7,0))-2*a(5,0)*l(8,0))-2*l(5,0)*a(8,0)); groebnerMatrix(3,33) = (((((((((((-2*a(3,0)*k(6,0)+2*a(3,0)*k(3,0))+2*a(4,0)*k(4,0))+2*a(5,0)*k(5,0))+2*a(6,0)*k(6,0))+2*a(7,0)*k(7,0))+2*a(8,0)*k(8,0))-2*k(3,0)*a(6,0))-2*a(4,0)*k(7,0))-2*k(4,0)*a(7,0))-2*a(5,0)*k(8,0))-2*k(5,0)*a(8,0)); groebnerMatrix(3,34) = (((((((((((-2*a(3,0)*m(6,0)+2*a(3,0)*m(3,0))+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(6,0)*m(6,0))+2*a(7,0)*m(7,0))+2*a(8,0)*m(8,0))-2*m(3,0)*a(6,0))-2*a(4,0)*m(7,0))-2*m(4,0)*a(7,0))-2*a(5,0)*m(8,0))-2*m(5,0)*a(8,0)); groebnerMatrix(3,35) = (((((((((((-2*n(3,0)*a(6,0)-2*a(3,0)*n(6,0))+2*a(3,0)*n(3,0))+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(6,0)*n(6,0))+2*a(7,0)*n(7,0))+2*a(8,0)*n(8,0))-2*a(4,0)*n(7,0))-2*n(4,0)*a(7,0))-2*a(5,0)*n(8,0))-2*n(5,0)*a(8,0)); groebnerMatrix(3,36) = (((((((((-c12w+pow(a(3,0),2))+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(6,0),2))+pow(a(7,0),2))+pow(a(8,0),2))-2*a(3,0)*a(6,0))-2*a(4,0)*a(7,0))-2*a(5,0)*a(8,0)); groebnerMatrix(4,22) = ((((((((pow(l(3,0),2)+pow(l(4,0),2))+pow(l(5,0),2))-2*l(3,0)*l(9,0))-2*l(4,0)*l(10,0))-2*l(5,0)*l(11,0))+pow(l(9,0),2))+pow(l(10,0),2))+pow(l(11,0),2)); groebnerMatrix(4,23) = (((((((((((2*k(3,0)*l(3,0)+2*k(4,0)*l(4,0))+2*k(5,0)*l(5,0))+2*k(9,0)*l(9,0))+2*k(10,0)*l(10,0))+2*k(11,0)*l(11,0))-2*k(3,0)*l(9,0))-2*l(3,0)*k(9,0))-2*k(4,0)*l(10,0))-2*l(4,0)*k(10,0))-2*k(5,0)*l(11,0))-2*l(5,0)*k(11,0)); groebnerMatrix(4,24) = ((((((((pow(k(3,0),2)+pow(k(4,0),2))+pow(k(5,0),2))-2*k(3,0)*k(9,0))-2*k(4,0)*k(10,0))-2*k(5,0)*k(11,0))+pow(k(9,0),2))+pow(k(10,0),2))+pow(k(11,0),2)); groebnerMatrix(4,25) = (((((((((((2*m(3,0)*l(3,0)+2*m(4,0)*l(4,0))+2*m(5,0)*l(5,0))+2*m(9,0)*l(9,0))+2*m(10,0)*l(10,0))+2*m(11,0)*l(11,0))-2*m(3,0)*l(9,0))-2*l(3,0)*m(9,0))-2*m(4,0)*l(10,0))-2*l(4,0)*m(10,0))-2*m(5,0)*l(11,0))-2*l(5,0)*m(11,0)); groebnerMatrix(4,26) = (((((((((((2*m(3,0)*k(3,0)+2*m(4,0)*k(4,0))+2*m(5,0)*k(5,0))+2*m(9,0)*k(9,0))+2*m(10,0)*k(10,0))+2*m(11,0)*k(11,0))-2*m(3,0)*k(9,0))-2*k(3,0)*m(9,0))-2*m(4,0)*k(10,0))-2*k(4,0)*m(10,0))-2*m(5,0)*k(11,0))-2*k(5,0)*m(11,0)); groebnerMatrix(4,27) = ((((((((pow(m(3,0),2)+pow(m(4,0),2))+pow(m(5,0),2))-2*m(3,0)*m(9,0))-2*m(4,0)*m(10,0))-2*m(5,0)*m(11,0))+pow(m(9,0),2))+pow(m(10,0),2))+pow(m(11,0),2)); groebnerMatrix(4,28) = (((((((((((2*n(3,0)*l(3,0)+2*n(4,0)*l(4,0))+2*n(5,0)*l(5,0))+2*n(9,0)*l(9,0))+2*n(10,0)*l(10,0))+2*n(11,0)*l(11,0))-2*n(3,0)*l(9,0))-2*l(3,0)*n(9,0))-2*n(4,0)*l(10,0))-2*l(4,0)*n(10,0))-2*n(5,0)*l(11,0))-2*l(5,0)*n(11,0)); groebnerMatrix(4,29) = (((((((((((2*n(3,0)*k(3,0)+2*n(4,0)*k(4,0))+2*n(5,0)*k(5,0))+2*n(9,0)*k(9,0))+2*n(10,0)*k(10,0))+2*n(11,0)*k(11,0))-2*n(3,0)*k(9,0))-2*k(3,0)*n(9,0))-2*n(4,0)*k(10,0))-2*k(4,0)*n(10,0))-2*n(5,0)*k(11,0))-2*k(5,0)*n(11,0)); groebnerMatrix(4,30) = (((((((((((2*n(3,0)*m(3,0)+2*n(4,0)*m(4,0))+2*n(5,0)*m(5,0))+2*n(9,0)*m(9,0))+2*n(10,0)*m(10,0))+2*n(11,0)*m(11,0))-2*n(3,0)*m(9,0))-2*m(3,0)*n(9,0))-2*n(4,0)*m(10,0))-2*m(4,0)*n(10,0))-2*n(5,0)*m(11,0))-2*m(5,0)*n(11,0)); groebnerMatrix(4,31) = ((((((((pow(n(3,0),2)+pow(n(4,0),2))+pow(n(5,0),2))-2*n(3,0)*n(9,0))-2*n(4,0)*n(10,0))-2*n(5,0)*n(11,0))+pow(n(9,0),2))+pow(n(10,0),2))+pow(n(11,0),2)); groebnerMatrix(4,32) = (((((((((((2*a(3,0)*l(3,0)+2*a(4,0)*l(4,0))+2*a(5,0)*l(5,0))+2*a(9,0)*l(9,0))+2*a(10,0)*l(10,0))+2*a(11,0)*l(11,0))-2*a(3,0)*l(9,0))-2*l(3,0)*a(9,0))-2*a(4,0)*l(10,0))-2*l(4,0)*a(10,0))-2*a(5,0)*l(11,0))-2*l(5,0)*a(11,0)); groebnerMatrix(4,33) = (((((((((((2*a(3,0)*k(3,0)+2*a(4,0)*k(4,0))+2*a(5,0)*k(5,0))+2*a(9,0)*k(9,0))+2*a(10,0)*k(10,0))+2*a(11,0)*k(11,0))-2*a(3,0)*k(9,0))-2*k(3,0)*a(9,0))-2*a(4,0)*k(10,0))-2*k(4,0)*a(10,0))-2*a(5,0)*k(11,0))-2*k(5,0)*a(11,0)); groebnerMatrix(4,34) = (((((((((((2*a(3,0)*m(3,0)+2*a(4,0)*m(4,0))+2*a(5,0)*m(5,0))+2*a(9,0)*m(9,0))+2*a(10,0)*m(10,0))+2*a(11,0)*m(11,0))-2*a(3,0)*m(9,0))-2*m(3,0)*a(9,0))-2*a(4,0)*m(10,0))-2*m(4,0)*a(10,0))-2*a(5,0)*m(11,0))-2*m(5,0)*a(11,0)); groebnerMatrix(4,35) = (((((((((((2*a(3,0)*n(3,0)+2*a(4,0)*n(4,0))+2*a(5,0)*n(5,0))+2*a(9,0)*n(9,0))+2*a(10,0)*n(10,0))+2*a(11,0)*n(11,0))-2*a(3,0)*n(9,0))-2*n(3,0)*a(9,0))-2*a(4,0)*n(10,0))-2*n(4,0)*a(10,0))-2*a(5,0)*n(11,0))-2*n(5,0)*a(11,0)); groebnerMatrix(4,36) = (((((((((-c13w+pow(a(3,0),2))+pow(a(4,0),2))+pow(a(5,0),2))+pow(a(9,0),2))+pow(a(10,0),2))+pow(a(11,0),2))-2*a(3,0)*a(9,0))-2*a(4,0)*a(10,0))-2*a(5,0)*a(11,0)); } opengv/src/absolute_pose/modules/gpnp4/code.cpp0000664016516101651610000003203413344612246020562 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp4::compute( Eigen::Matrix & groebnerMatrix ) { sPolynomial5(groebnerMatrix); sPolynomial6(groebnerMatrix); groebnerRow5_0000_f(groebnerMatrix,6); sPolynomial7(groebnerMatrix); groebnerRow5_0000_f(groebnerMatrix,7); groebnerRow6_0000_f(groebnerMatrix,7); sPolynomial8(groebnerMatrix); groebnerRow5_0000_f(groebnerMatrix,8); groebnerRow6_0000_f(groebnerMatrix,8); groebnerRow7_0000_f(groebnerMatrix,8); sPolynomial9(groebnerMatrix); groebnerRow7_0100_f(groebnerMatrix,9); groebnerRow8_0100_f(groebnerMatrix,9); groebnerRow5_1000_f(groebnerMatrix,9); groebnerRow6_1000_f(groebnerMatrix,9); groebnerRow7_1000_f(groebnerMatrix,9); groebnerRow8_1000_f(groebnerMatrix,9); groebnerRow5_0000_f(groebnerMatrix,9); groebnerRow6_0000_f(groebnerMatrix,9); groebnerRow7_0000_f(groebnerMatrix,9); groebnerRow8_0000_f(groebnerMatrix,9); sPolynomial10(groebnerMatrix); groebnerRow6_0100_f(groebnerMatrix,10); groebnerRow7_0100_f(groebnerMatrix,10); groebnerRow8_0100_f(groebnerMatrix,10); groebnerRow9_0000_f(groebnerMatrix,10); groebnerRow5_1000_f(groebnerMatrix,10); groebnerRow6_1000_f(groebnerMatrix,10); groebnerRow7_1000_f(groebnerMatrix,10); groebnerRow8_1000_f(groebnerMatrix,10); groebnerRow5_0000_f(groebnerMatrix,10); groebnerRow6_0000_f(groebnerMatrix,10); groebnerRow7_0000_f(groebnerMatrix,10); groebnerRow8_0000_f(groebnerMatrix,10); sPolynomial11(groebnerMatrix); groebnerRow6_0100_f(groebnerMatrix,11); groebnerRow7_0100_f(groebnerMatrix,11); groebnerRow8_0100_f(groebnerMatrix,11); groebnerRow9_0000_f(groebnerMatrix,11); groebnerRow4_1000_f(groebnerMatrix,11); groebnerRow5_1000_f(groebnerMatrix,11); groebnerRow6_1000_f(groebnerMatrix,11); groebnerRow7_1000_f(groebnerMatrix,11); groebnerRow8_1000_f(groebnerMatrix,11); groebnerRow10_0000_f(groebnerMatrix,11); groebnerRow4_0000_f(groebnerMatrix,11); groebnerRow5_0000_f(groebnerMatrix,11); groebnerRow6_0000_f(groebnerMatrix,11); groebnerRow7_0000_f(groebnerMatrix,11); groebnerRow8_0000_f(groebnerMatrix,11); sPolynomial12(groebnerMatrix); groebnerRow5_0100_f(groebnerMatrix,12); groebnerRow6_0100_f(groebnerMatrix,12); groebnerRow7_0100_f(groebnerMatrix,12); groebnerRow8_0100_f(groebnerMatrix,12); groebnerRow9_0000_f(groebnerMatrix,12); groebnerRow4_1000_f(groebnerMatrix,12); groebnerRow5_1000_f(groebnerMatrix,12); groebnerRow6_1000_f(groebnerMatrix,12); groebnerRow7_1000_f(groebnerMatrix,12); groebnerRow8_1000_f(groebnerMatrix,12); groebnerRow10_0000_f(groebnerMatrix,12); groebnerRow11_0000_f(groebnerMatrix,12); groebnerRow4_0000_f(groebnerMatrix,12); groebnerRow5_0000_f(groebnerMatrix,12); groebnerRow6_0000_f(groebnerMatrix,12); groebnerRow7_0000_f(groebnerMatrix,12); groebnerRow8_0000_f(groebnerMatrix,12); sPolynomial13(groebnerMatrix); groebnerRow6_0010_f(groebnerMatrix,13); groebnerRow4_0100_f(groebnerMatrix,13); groebnerRow5_0100_f(groebnerMatrix,13); groebnerRow6_0100_f(groebnerMatrix,13); groebnerRow7_0100_f(groebnerMatrix,13); groebnerRow8_0100_f(groebnerMatrix,13); groebnerRow9_0000_f(groebnerMatrix,13); groebnerRow4_1000_f(groebnerMatrix,13); groebnerRow5_1000_f(groebnerMatrix,13); groebnerRow6_1000_f(groebnerMatrix,13); groebnerRow7_1000_f(groebnerMatrix,13); groebnerRow8_1000_f(groebnerMatrix,13); groebnerRow10_0000_f(groebnerMatrix,13); groebnerRow11_0000_f(groebnerMatrix,13); groebnerRow12_0000_f(groebnerMatrix,13); groebnerRow4_0000_f(groebnerMatrix,13); groebnerRow5_0000_f(groebnerMatrix,13); groebnerRow6_0000_f(groebnerMatrix,13); groebnerRow7_0000_f(groebnerMatrix,13); groebnerRow8_0000_f(groebnerMatrix,13); sPolynomial14(groebnerMatrix); groebnerRow5_0010_f(groebnerMatrix,14); groebnerRow6_0010_f(groebnerMatrix,14); groebnerRow4_0100_f(groebnerMatrix,14); groebnerRow5_0100_f(groebnerMatrix,14); groebnerRow6_0100_f(groebnerMatrix,14); groebnerRow7_0100_f(groebnerMatrix,14); groebnerRow8_0100_f(groebnerMatrix,14); groebnerRow9_0000_f(groebnerMatrix,14); groebnerRow4_1000_f(groebnerMatrix,14); groebnerRow5_1000_f(groebnerMatrix,14); groebnerRow6_1000_f(groebnerMatrix,14); groebnerRow7_1000_f(groebnerMatrix,14); groebnerRow8_1000_f(groebnerMatrix,14); groebnerRow10_0000_f(groebnerMatrix,14); groebnerRow11_0000_f(groebnerMatrix,14); groebnerRow12_0000_f(groebnerMatrix,14); groebnerRow13_0000_f(groebnerMatrix,14); groebnerRow4_0000_f(groebnerMatrix,14); groebnerRow5_0000_f(groebnerMatrix,14); groebnerRow6_0000_f(groebnerMatrix,14); groebnerRow7_0000_f(groebnerMatrix,14); groebnerRow8_0000_f(groebnerMatrix,14); sPolynomial15(groebnerMatrix); groebnerRow14_1000_f(groebnerMatrix,15); groebnerRow9_0000_f(groebnerMatrix,15); groebnerRow7_1000_f(groebnerMatrix,15); groebnerRow8_1000_f(groebnerMatrix,15); groebnerRow10_0000_f(groebnerMatrix,15); groebnerRow11_0000_f(groebnerMatrix,15); groebnerRow12_0000_f(groebnerMatrix,15); groebnerRow13_0000_f(groebnerMatrix,15); groebnerRow14_0000_f(groebnerMatrix,15); groebnerRow7_0000_f(groebnerMatrix,15); groebnerRow8_0000_f(groebnerMatrix,15); sPolynomial16(groebnerMatrix); groebnerRow13_1000_f(groebnerMatrix,16); groebnerRow14_1000_f(groebnerMatrix,16); groebnerRow8_0100_f(groebnerMatrix,16); groebnerRow15_0100_f(groebnerMatrix,16); groebnerRow5_1000_f(groebnerMatrix,16); groebnerRow6_1000_f(groebnerMatrix,16); groebnerRow7_1000_f(groebnerMatrix,16); groebnerRow8_1000_f(groebnerMatrix,16); groebnerRow15_1000_f(groebnerMatrix,16); groebnerRow11_0000_f(groebnerMatrix,16); groebnerRow12_0000_f(groebnerMatrix,16); groebnerRow13_0000_f(groebnerMatrix,16); groebnerRow14_0000_f(groebnerMatrix,16); groebnerRow5_0000_f(groebnerMatrix,16); groebnerRow6_0000_f(groebnerMatrix,16); groebnerRow7_0000_f(groebnerMatrix,16); groebnerRow8_0000_f(groebnerMatrix,16); groebnerRow15_0000_f(groebnerMatrix,16); sPolynomial17(groebnerMatrix); groebnerRow12_1000_f(groebnerMatrix,17); groebnerRow13_1000_f(groebnerMatrix,17); groebnerRow14_1000_f(groebnerMatrix,17); groebnerRow7_0100_f(groebnerMatrix,17); groebnerRow8_0100_f(groebnerMatrix,17); groebnerRow15_0100_f(groebnerMatrix,17); groebnerRow4_1000_f(groebnerMatrix,17); groebnerRow5_1000_f(groebnerMatrix,17); groebnerRow6_1000_f(groebnerMatrix,17); groebnerRow7_1000_f(groebnerMatrix,17); groebnerRow8_1000_f(groebnerMatrix,17); groebnerRow15_1000_f(groebnerMatrix,17); groebnerRow16_1000_f(groebnerMatrix,17); groebnerRow12_0000_f(groebnerMatrix,17); groebnerRow13_0000_f(groebnerMatrix,17); groebnerRow14_0000_f(groebnerMatrix,17); groebnerRow4_0000_f(groebnerMatrix,17); groebnerRow5_0000_f(groebnerMatrix,17); groebnerRow6_0000_f(groebnerMatrix,17); groebnerRow7_0000_f(groebnerMatrix,17); groebnerRow8_0000_f(groebnerMatrix,17); groebnerRow15_0000_f(groebnerMatrix,17); groebnerRow16_0000_f(groebnerMatrix,17); sPolynomial18(groebnerMatrix); groebnerRow14_0001_f(groebnerMatrix,18); groebnerRow14_0010_f(groebnerMatrix,18); groebnerRow13_1000_f(groebnerMatrix,18); groebnerRow14_1000_f(groebnerMatrix,18); groebnerRow7_0100_f(groebnerMatrix,18); groebnerRow8_0100_f(groebnerMatrix,18); groebnerRow15_0100_f(groebnerMatrix,18); groebnerRow4_1000_f(groebnerMatrix,18); groebnerRow5_1000_f(groebnerMatrix,18); groebnerRow6_1000_f(groebnerMatrix,18); groebnerRow7_1000_f(groebnerMatrix,18); groebnerRow8_1000_f(groebnerMatrix,18); groebnerRow15_1000_f(groebnerMatrix,18); groebnerRow16_1000_f(groebnerMatrix,18); groebnerRow17_1000_f(groebnerMatrix,18); groebnerRow13_0000_f(groebnerMatrix,18); groebnerRow14_0000_f(groebnerMatrix,18); groebnerRow4_0000_f(groebnerMatrix,18); groebnerRow5_0000_f(groebnerMatrix,18); groebnerRow6_0000_f(groebnerMatrix,18); groebnerRow7_0000_f(groebnerMatrix,18); groebnerRow8_0000_f(groebnerMatrix,18); groebnerRow15_0000_f(groebnerMatrix,18); groebnerRow16_0000_f(groebnerMatrix,18); groebnerRow17_0000_f(groebnerMatrix,18); sPolynomial19(groebnerMatrix); groebnerRow14_0000_f(groebnerMatrix,19); groebnerRow15_0000_f(groebnerMatrix,19); groebnerRow16_0000_f(groebnerMatrix,19); groebnerRow17_0000_f(groebnerMatrix,19); groebnerRow18_0000_f(groebnerMatrix,19); sPolynomial20(groebnerMatrix); groebnerRow18_1000_f(groebnerMatrix,20); groebnerRow19_1000_f(groebnerMatrix,20); groebnerRow15_0000_f(groebnerMatrix,20); groebnerRow16_0000_f(groebnerMatrix,20); groebnerRow17_0000_f(groebnerMatrix,20); groebnerRow18_0000_f(groebnerMatrix,20); groebnerRow19_0000_f(groebnerMatrix,20); sPolynomial21(groebnerMatrix); groebnerRow17_1000_f(groebnerMatrix,21); groebnerRow18_1000_f(groebnerMatrix,21); groebnerRow19_1000_f(groebnerMatrix,21); groebnerRow15_0000_f(groebnerMatrix,21); groebnerRow20_1000_f(groebnerMatrix,21); groebnerRow17_0000_f(groebnerMatrix,21); groebnerRow18_0000_f(groebnerMatrix,21); groebnerRow19_0000_f(groebnerMatrix,21); groebnerRow20_0000_f(groebnerMatrix,21); sPolynomial22(groebnerMatrix); groebnerRow19_0001_f(groebnerMatrix,22); groebnerRow19_0010_f(groebnerMatrix,22); groebnerRow18_1000_f(groebnerMatrix,22); groebnerRow19_1000_f(groebnerMatrix,22); groebnerRow20_0001_f(groebnerMatrix,22); groebnerRow20_0010_f(groebnerMatrix,22); groebnerRow21_0010_f(groebnerMatrix,22); groebnerRow20_0100_f(groebnerMatrix,22); groebnerRow21_0100_f(groebnerMatrix,22); groebnerRow15_0000_f(groebnerMatrix,22); groebnerRow20_1000_f(groebnerMatrix,22); groebnerRow21_1000_f(groebnerMatrix,22); groebnerRow18_0000_f(groebnerMatrix,22); groebnerRow19_0000_f(groebnerMatrix,22); groebnerRow20_0000_f(groebnerMatrix,22); groebnerRow21_0000_f(groebnerMatrix,22); sPolynomial23(groebnerMatrix); groebnerRow20_1100_f(groebnerMatrix,23); groebnerRow21_1100_f(groebnerMatrix,23); groebnerRow22_1100_f(groebnerMatrix,23); groebnerRow19_0001_f(groebnerMatrix,23); groebnerRow19_0010_f(groebnerMatrix,23); groebnerRow19_0100_f(groebnerMatrix,23); groebnerRow19_1000_f(groebnerMatrix,23); groebnerRow20_0001_f(groebnerMatrix,23); groebnerRow20_0010_f(groebnerMatrix,23); groebnerRow21_0010_f(groebnerMatrix,23); groebnerRow20_0100_f(groebnerMatrix,23); groebnerRow21_0100_f(groebnerMatrix,23); groebnerRow22_0100_f(groebnerMatrix,23); groebnerRow20_1000_f(groebnerMatrix,23); groebnerRow21_1000_f(groebnerMatrix,23); groebnerRow22_1000_f(groebnerMatrix,23); groebnerRow19_0000_f(groebnerMatrix,23); groebnerRow20_0000_f(groebnerMatrix,23); groebnerRow21_0000_f(groebnerMatrix,23); groebnerRow22_0000_f(groebnerMatrix,23); sPolynomial24(groebnerMatrix); groebnerRow20_0000_f(groebnerMatrix,24); groebnerRow21_0000_f(groebnerMatrix,24); groebnerRow22_0000_f(groebnerMatrix,24); groebnerRow23_0000_f(groebnerMatrix,24); } opengv/src/absolute_pose/modules/gpnp1/0000775016516101651610000000000013344612246017137 5ustar dimadimaopengv/src/absolute_pose/modules/gpnp1/reductors.cpp0000664016516101651610000000516713344612246021666 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp1::groebnerRow3_0_f( Eigen::Matrix & groebnerMatrix, int targetRow ) { double factor = groebnerMatrix(targetRow,1) / groebnerMatrix(3,1); groebnerMatrix(targetRow,1) = 0.0; groebnerMatrix(targetRow,2) -= factor * groebnerMatrix(3,2); } opengv/src/absolute_pose/modules/gpnp1/spolynomials.cpp0000664016516101651610000000574313344612246022405 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp1::sPolynomial3( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(3,1) = (groebnerMatrix(0,1)/(groebnerMatrix(0,0))-groebnerMatrix(1,1)/(groebnerMatrix(1,0))); groebnerMatrix(3,2) = (groebnerMatrix(0,2)/(groebnerMatrix(0,0))-groebnerMatrix(1,2)/(groebnerMatrix(1,0))); } void opengv::absolute_pose::modules::gpnp1::sPolynomial4( Eigen::Matrix & groebnerMatrix ) { groebnerMatrix(4,1) = (groebnerMatrix(1,1)/(groebnerMatrix(1,0))-groebnerMatrix(2,1)/(groebnerMatrix(2,0))); groebnerMatrix(4,2) = (groebnerMatrix(1,2)/(groebnerMatrix(1,0))-groebnerMatrix(2,2)/(groebnerMatrix(2,0))); } opengv/src/absolute_pose/modules/gpnp1/init.cpp0000664016516101651610000001060613344612246020611 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp1::init( Eigen::Matrix & groebnerMatrix, const Eigen::Matrix & a, Eigen::Matrix & n, Eigen::Vector3d & c0, Eigen::Vector3d & c1, Eigen::Vector3d & c2, Eigen::Vector3d & c3 ) { Eigen::Vector3d temp = c0-c1; double c01w = temp.norm()*temp.norm(); temp = c0-c2; double c02w = temp.norm()*temp.norm(); temp = c0-c3; double c03w = temp.norm()*temp.norm(); groebnerMatrix(0,0) = -2*n(0,0)*n(3,0)-2*n(1,0)*n(4,0)-2*n(2,0)*n(5,0)+pow(n(0,0),2)+pow(n(3,0),2)+pow(n(1,0),2)+pow(n(4,0),2)+pow(n(2,0),2)+pow(n(5,0),2); groebnerMatrix(0,1) = 2*a(0,0)*n(0,0)-2*a(0,0)*n(3,0)-2*n(0,0)*a(3,0)+2*a(3,0)*n(3,0)+2*a(1,0)*n(1,0)-2*a(1,0)*n(4,0)-2*n(1,0)*a(4,0)+2*a(4,0)*n(4,0)+2*a(2,0)*n(2,0)-2*a(2,0)*n(5,0)-2*n(2,0)*a(5,0)+2*a(5,0)*n(5,0); groebnerMatrix(0,2) = -c01w+pow(a(0,0),2)-2*a(0,0)*a(3,0)+pow(a(3,0),2)+pow(a(1,0),2)-2*a(1,0)*a(4,0)+pow(a(4,0),2)+pow(a(2,0),2)-2*a(2,0)*a(5,0)+pow(a(5,0),2); groebnerMatrix(1,0) = -2*n(0,0)*n(6,0)-2*n(1,0)*n(7,0)-2*n(2,0)*n(8,0)+pow(n(0,0),2)+pow(n(1,0),2)+pow(n(2,0),2)+pow(n(6,0),2)+pow(n(7,0),2)+pow(n(8,0),2); groebnerMatrix(1,1) = 2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0)+2*a(2,0)*n(2,0)-2*a(0,0)*n(6,0)-2*n(0,0)*a(6,0)+2*a(6,0)*n(6,0)-2*a(1,0)*n(7,0)-2*n(1,0)*a(7,0)+2*a(7,0)*n(7,0)-2*a(2,0)*n(8,0)-2*n(2,0)*a(8,0)+2*a(8,0)*n(8,0); groebnerMatrix(1,2) = -c02w+pow(a(0,0),2)+pow(a(1,0),2)+pow(a(2,0),2)-2*a(0,0)*a(6,0)+pow(a(6,0),2)-2*a(1,0)*a(7,0)+pow(a(7,0),2)-2*a(2,0)*a(8,0)+pow(a(8,0),2); groebnerMatrix(2,0) = -2*n(0,0)*n(9,0)-2*n(1,0)*n(10,0)-2*n(2,0)*n(11,0)+pow(n(0,0),2)+pow(n(1,0),2)+pow(n(2,0),2)+pow(n(9,0),2)+pow(n(10,0),2)+pow(n(11,0),2); groebnerMatrix(2,1) = 2*a(0,0)*n(0,0)+2*a(1,0)*n(1,0)+2*a(2,0)*n(2,0)-2*a(0,0)*n(9,0)-2*n(0,0)*a(9,0)+2*a(9,0)*n(9,0)-2*a(1,0)*n(10,0)-2*n(1,0)*a(10,0)+2*a(10,0)*n(10,0)-2*a(2,0)*n(11,0)-2*n(2,0)*a(11,0)+2*a(11,0)*n(11,0); groebnerMatrix(2,2) = -c03w+pow(a(0,0),2)+pow(a(1,0),2)+pow(a(2,0),2)-2*a(0,0)*a(9,0)+pow(a(9,0),2)-2*a(1,0)*a(10,0)+pow(a(10,0),2)-2*a(2,0)*a(11,0)+pow(a(11,0),2); } opengv/src/absolute_pose/modules/gpnp1/code.cpp0000664016516101651610000000504113344612246020555 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include void opengv::absolute_pose::modules::gpnp1::compute( Eigen::Matrix & groebnerMatrix ) { sPolynomial3(groebnerMatrix); sPolynomial4(groebnerMatrix); groebnerRow3_0_f(groebnerMatrix,4); } opengv/src/absolute_pose/modules/upnp2.cpp0000664016516101651610000064145013344612246017674 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include void opengv::absolute_pose::modules::upnp::setupAction_gj( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, Eigen::Matrix & Action ) { Eigen::Matrix M1 = Eigen::Matrix::Zero(); M1(0,0) = 4*M(0,0); M1(0,1) = 4*M(4,0)+2*M(0,4); M1(0,2) = 2*M(4,4)+4*M(1,0); M1(0,3) = 2*M(1,4); M1(0,4) = 4*M(5,0)+2*M(0,5); M1(0,5) = 4*M(7,0)+2*M(5,4)+2*M(4,5); M1(0,6) = 2*M(7,4)+2*M(1,5); M1(0,7) = 2*M(5,5)+4*M(2,0); M1(0,8) = 2*M(7,5)+2*M(2,4); M1(0,9) = 2*M(2,5); M1(0,10) = 4*M(6,0)+2*M(0,6); M1(0,11) = 4*M(8,0)+2*M(6,4)+2*M(4,6); M1(0,12) = 2*M(8,4)+2*M(1,6); M1(0,13) = 4*M(9,0)+2*M(6,5)+2*M(5,6); M1(0,14) = 2*M(9,4)+2*M(8,5)+2*M(7,6); M1(0,15) = 2*M(9,5)+2*M(2,6); M1(0,16) = 2*M(6,6)+4*M(3,0); M1(0,17) = 2*M(8,6)+2*M(3,4); M1(0,18) = 2*M(9,6)+2*M(3,5); M1(0,19) = 2*M(3,6); M1(0,24) = 4*C(0,0); M1(0,25) = 2*C(0,4); M1(0,26) = 2*C(0,5); M1(0,27) = 2*C(0,6); M1(1,0) = 2*M(0,4); M1(1,1) = 2*M(4,4)+4*M(0,1); M1(1,2) = 4*M(4,1)+2*M(1,4); M1(1,3) = 4*M(1,1); M1(1,4) = 2*M(5,4)+2*M(0,7); M1(1,5) = 2*M(7,4)+4*M(5,1)+2*M(4,7); M1(1,6) = 4*M(7,1)+2*M(1,7); M1(1,7) = 2*M(5,7)+2*M(2,4); M1(1,8) = 2*M(7,7)+4*M(2,1); M1(1,9) = 2*M(2,7); M1(1,10) = 2*M(6,4)+2*M(0,8); M1(1,11) = 2*M(8,4)+4*M(6,1)+2*M(4,8); M1(1,12) = 4*M(8,1)+2*M(1,8); M1(1,13) = 2*M(9,4)+2*M(6,7)+2*M(5,8); M1(1,14) = 4*M(9,1)+2*M(8,7)+2*M(7,8); M1(1,15) = 2*M(9,7)+2*M(2,8); M1(1,16) = 2*M(6,8)+2*M(3,4); M1(1,17) = 2*M(8,8)+4*M(3,1); M1(1,18) = 2*M(9,8)+2*M(3,7); M1(1,19) = 2*M(3,8); M1(1,24) = 2*C(0,4); M1(1,25) = 4*C(0,1); M1(1,26) = 2*C(0,7); M1(1,27) = 2*C(0,8); M1(2,0) = 2*M(0,5); M1(2,1) = 2*M(4,5)+2*M(0,7); M1(2,2) = 2*M(4,7)+2*M(1,5); M1(2,3) = 2*M(1,7); M1(2,4) = 2*M(5,5)+4*M(0,2); M1(2,5) = 2*M(7,5)+2*M(5,7)+4*M(4,2); M1(2,6) = 2*M(7,7)+4*M(1,2); M1(2,7) = 4*M(5,2)+2*M(2,5); M1(2,8) = 4*M(7,2)+2*M(2,7); M1(2,9) = 4*M(2,2); M1(2,10) = 2*M(6,5)+2*M(0,9); M1(2,11) = 2*M(8,5)+2*M(6,7)+2*M(4,9); M1(2,12) = 2*M(8,7)+2*M(1,9); M1(2,13) = 2*M(9,5)+4*M(6,2)+2*M(5,9); M1(2,14) = 2*M(9,7)+4*M(8,2)+2*M(7,9); M1(2,15) = 4*M(9,2)+2*M(2,9); M1(2,16) = 2*M(6,9)+2*M(3,5); M1(2,17) = 2*M(8,9)+2*M(3,7); M1(2,18) = 2*M(9,9)+4*M(3,2); M1(2,19) = 2*M(3,9); M1(2,24) = 2*C(0,5); M1(2,25) = 2*C(0,7); M1(2,26) = 4*C(0,2); M1(2,27) = 2*C(0,9); M1(3,0) = 2*M(0,6); M1(3,1) = 2*M(4,6)+2*M(0,8); M1(3,2) = 2*M(4,8)+2*M(1,6); M1(3,3) = 2*M(1,8); M1(3,4) = 2*M(5,6)+2*M(0,9); M1(3,5) = 2*M(7,6)+2*M(5,8)+2*M(4,9); M1(3,6) = 2*M(7,8)+2*M(1,9); M1(3,7) = 2*M(5,9)+2*M(2,6); M1(3,8) = 2*M(7,9)+2*M(2,8); M1(3,9) = 2*M(2,9); M1(3,10) = 2*M(6,6)+4*M(0,3); M1(3,11) = 2*M(8,6)+2*M(6,8)+4*M(4,3); M1(3,12) = 2*M(8,8)+4*M(1,3); M1(3,13) = 2*M(9,6)+2*M(6,9)+4*M(5,3); M1(3,14) = 2*M(9,8)+2*M(8,9)+4*M(7,3); M1(3,15) = 2*M(9,9)+4*M(2,3); M1(3,16) = 4*M(6,3)+2*M(3,6); M1(3,17) = 4*M(8,3)+2*M(3,8); M1(3,18) = 4*M(9,3)+2*M(3,9); M1(3,19) = 4*M(3,3); M1(3,24) = 2*C(0,6); M1(3,25) = 2*C(0,8); M1(3,26) = 2*C(0,9); M1(3,27) = 4*C(0,3); M1(4,20) = 1; M1(4,21) = 1; M1(4,22) = 1; M1(4,23) = 1; M1(4,28) = -1; Eigen::Matrix M1_part1 = M1.block<4,4>(0,0); Eigen::Matrix M1_part2 = M1_part1.inverse() * M1.block<4,29>(0,0); M1.block<4,29>(0,0) = M1_part2; std::vector*> M2; for( int r = 0; r < 395; r++ ) { std::vector * row = new std::vector(); for( int c = 0; c < 412; c++ ) row->push_back(0.0); M2.push_back(row); } (*(M2[0]))[59] = M1(4,20); (*(M2[0]))[61] = M1(4,21); (*(M2[0]))[70] = M1(4,22); (*(M2[0]))[91] = M1(4,23); (*(M2[0]))[252] = M1(4,28); (*(M2[1]))[40] = M1(4,20); (*(M2[1]))[42] = M1(4,21); (*(M2[1]))[51] = M1(4,22); (*(M2[1]))[83] = M1(4,23); (*(M2[1]))[237] = M1(4,28); (*(M2[2]))[14] = M1(4,20); (*(M2[2]))[16] = M1(4,21); (*(M2[2]))[25] = M1(4,22); (*(M2[2]))[70] = M1(4,23); (*(M2[2]))[216] = M1(4,28); (*(M2[3]))[34] = M1(4,20); (*(M2[3]))[36] = M1(4,21); (*(M2[3]))[47] = M1(4,22); (*(M2[3]))[79] = M1(4,23); (*(M2[3]))[232] = M1(4,28); (*(M2[4]))[8] = M1(4,20); (*(M2[4]))[10] = M1(4,21); (*(M2[4]))[21] = M1(4,22); (*(M2[4]))[66] = M1(4,23); (*(M2[4]))[211] = M1(4,28); (*(M2[5]))[2] = M1(4,20); (*(M2[5]))[4] = M1(4,21); (*(M2[5]))[16] = M1(4,22); (*(M2[5]))[61] = M1(4,23); (*(M2[5]))[205] = M1(4,28); (*(M2[6]))[33] = M1(4,20); (*(M2[6]))[35] = M1(4,21); (*(M2[6]))[46] = M1(4,22); (*(M2[6]))[78] = M1(4,23); (*(M2[6]))[231] = M1(4,28); (*(M2[7]))[7] = M1(4,20); (*(M2[7]))[9] = M1(4,21); (*(M2[7]))[20] = M1(4,22); (*(M2[7]))[65] = M1(4,23); (*(M2[7]))[210] = M1(4,28); (*(M2[8]))[1] = M1(4,20); (*(M2[8]))[3] = M1(4,21); (*(M2[8]))[15] = M1(4,22); (*(M2[8]))[60] = M1(4,23); (*(M2[8]))[204] = M1(4,28); (*(M2[9]))[0] = M1(4,20); (*(M2[9]))[2] = M1(4,21); (*(M2[9]))[14] = M1(4,22); (*(M2[9]))[59] = M1(4,23); (*(M2[9]))[203] = M1(4,28); (*(M2[10]))[61] = M1(0,0); (*(M2[10]))[67] = M1(0,4); (*(M2[10]))[68] = M1(0,5); (*(M2[10]))[69] = M1(0,6); (*(M2[10]))[72] = M1(0,7); (*(M2[10]))[73] = M1(0,8); (*(M2[10]))[76] = M1(0,9); (*(M2[10]))[80] = M1(0,10); (*(M2[10]))[81] = M1(0,11); (*(M2[10]))[82] = M1(0,12); (*(M2[10]))[85] = M1(0,13); (*(M2[10]))[86] = M1(0,14); (*(M2[10]))[89] = M1(0,15); (*(M2[10]))[93] = M1(0,16); (*(M2[10]))[94] = M1(0,17); (*(M2[10]))[97] = M1(0,18); (*(M2[10]))[254] = M1(0,24); (*(M2[10]))[255] = M1(0,25); (*(M2[10]))[259] = M1(0,26); (*(M2[10]))[269] = M1(0,27); (*(M2[10]))[395] = M1(0,19); (*(M2[11]))[62] = M1(1,1); (*(M2[11]))[67] = M1(1,4); (*(M2[11]))[68] = M1(1,5); (*(M2[11]))[69] = M1(1,6); (*(M2[11]))[72] = M1(1,7); (*(M2[11]))[73] = M1(1,8); (*(M2[11]))[76] = M1(1,9); (*(M2[11]))[80] = M1(1,10); (*(M2[11]))[81] = M1(1,11); (*(M2[11]))[82] = M1(1,12); (*(M2[11]))[85] = M1(1,13); (*(M2[11]))[86] = M1(1,14); (*(M2[11]))[89] = M1(1,15); (*(M2[11]))[93] = M1(1,16); (*(M2[11]))[94] = M1(1,17); (*(M2[11]))[97] = M1(1,18); (*(M2[11]))[254] = M1(1,24); (*(M2[11]))[255] = M1(1,25); (*(M2[11]))[259] = M1(1,26); (*(M2[11]))[269] = M1(1,27); (*(M2[11]))[395] = M1(1,19); (*(M2[12]))[63] = M1(2,2); (*(M2[12]))[67] = M1(2,4); (*(M2[12]))[68] = M1(2,5); (*(M2[12]))[69] = M1(2,6); (*(M2[12]))[72] = M1(2,7); (*(M2[12]))[73] = M1(2,8); (*(M2[12]))[76] = M1(2,9); (*(M2[12]))[80] = M1(2,10); (*(M2[12]))[81] = M1(2,11); (*(M2[12]))[82] = M1(2,12); (*(M2[12]))[85] = M1(2,13); (*(M2[12]))[86] = M1(2,14); (*(M2[12]))[89] = M1(2,15); (*(M2[12]))[93] = M1(2,16); (*(M2[12]))[94] = M1(2,17); (*(M2[12]))[97] = M1(2,18); (*(M2[12]))[254] = M1(2,24); (*(M2[12]))[255] = M1(2,25); (*(M2[12]))[259] = M1(2,26); (*(M2[12]))[269] = M1(2,27); (*(M2[12]))[395] = M1(2,19); (*(M2[13]))[64] = M1(3,3); (*(M2[13]))[67] = M1(3,4); (*(M2[13]))[68] = M1(3,5); (*(M2[13]))[69] = M1(3,6); (*(M2[13]))[72] = M1(3,7); (*(M2[13]))[73] = M1(3,8); (*(M2[13]))[76] = M1(3,9); (*(M2[13]))[80] = M1(3,10); (*(M2[13]))[81] = M1(3,11); (*(M2[13]))[82] = M1(3,12); (*(M2[13]))[85] = M1(3,13); (*(M2[13]))[86] = M1(3,14); (*(M2[13]))[89] = M1(3,15); (*(M2[13]))[93] = M1(3,16); (*(M2[13]))[94] = M1(3,17); (*(M2[13]))[97] = M1(3,18); (*(M2[13]))[254] = M1(3,24); (*(M2[13]))[255] = M1(3,25); (*(M2[13]))[259] = M1(3,26); (*(M2[13]))[269] = M1(3,27); (*(M2[13]))[395] = M1(3,19); (*(M2[14]))[42] = M1(0,0); (*(M2[14]))[48] = M1(0,4); (*(M2[14]))[49] = M1(0,5); (*(M2[14]))[50] = M1(0,6); (*(M2[14]))[53] = M1(0,7); (*(M2[14]))[54] = M1(0,8); (*(M2[14]))[57] = M1(0,9); (*(M2[14]))[67] = M1(0,10); (*(M2[14]))[68] = M1(0,11); (*(M2[14]))[69] = M1(0,12); (*(M2[14]))[72] = M1(0,13); (*(M2[14]))[73] = M1(0,14); (*(M2[14]))[76] = M1(0,15); (*(M2[14]))[85] = M1(0,16); (*(M2[14]))[86] = M1(0,17); (*(M2[14]))[89] = M1(0,18); (*(M2[14]))[97] = M1(0,19); (*(M2[14]))[239] = M1(0,24); (*(M2[14]))[240] = M1(0,25); (*(M2[14]))[244] = M1(0,26); (*(M2[14]))[259] = M1(0,27); (*(M2[15]))[43] = M1(1,1); (*(M2[15]))[48] = M1(1,4); (*(M2[15]))[49] = M1(1,5); (*(M2[15]))[50] = M1(1,6); (*(M2[15]))[53] = M1(1,7); (*(M2[15]))[54] = M1(1,8); (*(M2[15]))[57] = M1(1,9); (*(M2[15]))[67] = M1(1,10); (*(M2[15]))[68] = M1(1,11); (*(M2[15]))[69] = M1(1,12); (*(M2[15]))[72] = M1(1,13); (*(M2[15]))[73] = M1(1,14); (*(M2[15]))[76] = M1(1,15); (*(M2[15]))[85] = M1(1,16); (*(M2[15]))[86] = M1(1,17); (*(M2[15]))[89] = M1(1,18); (*(M2[15]))[97] = M1(1,19); (*(M2[15]))[239] = M1(1,24); (*(M2[15]))[240] = M1(1,25); (*(M2[15]))[244] = M1(1,26); (*(M2[15]))[259] = M1(1,27); (*(M2[16]))[44] = M1(2,2); (*(M2[16]))[48] = M1(2,4); (*(M2[16]))[49] = M1(2,5); (*(M2[16]))[50] = M1(2,6); (*(M2[16]))[53] = M1(2,7); (*(M2[16]))[54] = M1(2,8); (*(M2[16]))[57] = M1(2,9); (*(M2[16]))[67] = M1(2,10); (*(M2[16]))[68] = M1(2,11); (*(M2[16]))[69] = M1(2,12); (*(M2[16]))[72] = M1(2,13); (*(M2[16]))[73] = M1(2,14); (*(M2[16]))[76] = M1(2,15); (*(M2[16]))[85] = M1(2,16); (*(M2[16]))[86] = M1(2,17); (*(M2[16]))[89] = M1(2,18); (*(M2[16]))[97] = M1(2,19); (*(M2[16]))[239] = M1(2,24); (*(M2[16]))[240] = M1(2,25); (*(M2[16]))[244] = M1(2,26); (*(M2[16]))[259] = M1(2,27); (*(M2[17]))[45] = M1(3,3); (*(M2[17]))[48] = M1(3,4); (*(M2[17]))[49] = M1(3,5); (*(M2[17]))[50] = M1(3,6); (*(M2[17]))[53] = M1(3,7); (*(M2[17]))[54] = M1(3,8); (*(M2[17]))[57] = M1(3,9); (*(M2[17]))[67] = M1(3,10); (*(M2[17]))[68] = M1(3,11); (*(M2[17]))[69] = M1(3,12); (*(M2[17]))[72] = M1(3,13); (*(M2[17]))[73] = M1(3,14); (*(M2[17]))[76] = M1(3,15); (*(M2[17]))[85] = M1(3,16); (*(M2[17]))[86] = M1(3,17); (*(M2[17]))[89] = M1(3,18); (*(M2[17]))[97] = M1(3,19); (*(M2[17]))[239] = M1(3,24); (*(M2[17]))[240] = M1(3,25); (*(M2[17]))[244] = M1(3,26); (*(M2[17]))[259] = M1(3,27); (*(M2[18]))[16] = M1(0,0); (*(M2[18]))[22] = M1(0,4); (*(M2[18]))[23] = M1(0,5); (*(M2[18]))[24] = M1(0,6); (*(M2[18]))[27] = M1(0,7); (*(M2[18]))[28] = M1(0,8); (*(M2[18]))[31] = M1(0,9); (*(M2[18]))[48] = M1(0,10); (*(M2[18]))[49] = M1(0,11); (*(M2[18]))[50] = M1(0,12); (*(M2[18]))[53] = M1(0,13); (*(M2[18]))[54] = M1(0,14); (*(M2[18]))[57] = M1(0,15); (*(M2[18]))[72] = M1(0,16); (*(M2[18]))[73] = M1(0,17); (*(M2[18]))[76] = M1(0,18); (*(M2[18]))[89] = M1(0,19); (*(M2[18]))[218] = M1(0,24); (*(M2[18]))[219] = M1(0,25); (*(M2[18]))[223] = M1(0,26); (*(M2[18]))[244] = M1(0,27); (*(M2[19]))[17] = M1(1,1); (*(M2[19]))[22] = M1(1,4); (*(M2[19]))[23] = M1(1,5); (*(M2[19]))[24] = M1(1,6); (*(M2[19]))[27] = M1(1,7); (*(M2[19]))[28] = M1(1,8); (*(M2[19]))[31] = M1(1,9); (*(M2[19]))[48] = M1(1,10); (*(M2[19]))[49] = M1(1,11); (*(M2[19]))[50] = M1(1,12); (*(M2[19]))[53] = M1(1,13); (*(M2[19]))[54] = M1(1,14); (*(M2[19]))[57] = M1(1,15); (*(M2[19]))[72] = M1(1,16); (*(M2[19]))[73] = M1(1,17); (*(M2[19]))[76] = M1(1,18); (*(M2[19]))[89] = M1(1,19); (*(M2[19]))[218] = M1(1,24); (*(M2[19]))[219] = M1(1,25); (*(M2[19]))[223] = M1(1,26); (*(M2[19]))[244] = M1(1,27); (*(M2[20]))[18] = M1(2,2); (*(M2[20]))[22] = M1(2,4); (*(M2[20]))[23] = M1(2,5); (*(M2[20]))[24] = M1(2,6); (*(M2[20]))[27] = M1(2,7); (*(M2[20]))[28] = M1(2,8); (*(M2[20]))[31] = M1(2,9); (*(M2[20]))[48] = M1(2,10); (*(M2[20]))[49] = M1(2,11); (*(M2[20]))[50] = M1(2,12); (*(M2[20]))[53] = M1(2,13); (*(M2[20]))[54] = M1(2,14); (*(M2[20]))[57] = M1(2,15); (*(M2[20]))[72] = M1(2,16); (*(M2[20]))[73] = M1(2,17); (*(M2[20]))[76] = M1(2,18); (*(M2[20]))[89] = M1(2,19); (*(M2[20]))[218] = M1(2,24); (*(M2[20]))[219] = M1(2,25); (*(M2[20]))[223] = M1(2,26); (*(M2[20]))[244] = M1(2,27); (*(M2[21]))[19] = M1(3,3); (*(M2[21]))[22] = M1(3,4); (*(M2[21]))[23] = M1(3,5); (*(M2[21]))[24] = M1(3,6); (*(M2[21]))[27] = M1(3,7); (*(M2[21]))[28] = M1(3,8); (*(M2[21]))[31] = M1(3,9); (*(M2[21]))[48] = M1(3,10); (*(M2[21]))[49] = M1(3,11); (*(M2[21]))[50] = M1(3,12); (*(M2[21]))[53] = M1(3,13); (*(M2[21]))[54] = M1(3,14); (*(M2[21]))[57] = M1(3,15); (*(M2[21]))[72] = M1(3,16); (*(M2[21]))[73] = M1(3,17); (*(M2[21]))[76] = M1(3,18); (*(M2[21]))[89] = M1(3,19); (*(M2[21]))[218] = M1(3,24); (*(M2[21]))[219] = M1(3,25); (*(M2[21]))[223] = M1(3,26); (*(M2[21]))[244] = M1(3,27); (*(M2[22]))[36] = M1(0,0); (*(M2[22]))[43] = M1(0,4); (*(M2[22]))[44] = M1(0,5); (*(M2[22]))[45] = M1(0,6); (*(M2[22]))[49] = M1(0,7); (*(M2[22]))[50] = M1(0,8); (*(M2[22]))[54] = M1(0,9); (*(M2[22]))[62] = M1(0,10); (*(M2[22]))[63] = M1(0,11); (*(M2[22]))[64] = M1(0,12); (*(M2[22]))[68] = M1(0,13); (*(M2[22]))[69] = M1(0,14); (*(M2[22]))[73] = M1(0,15); (*(M2[22]))[81] = M1(0,16); (*(M2[22]))[82] = M1(0,17); (*(M2[22]))[86] = M1(0,18); (*(M2[22]))[94] = M1(0,19); (*(M2[22]))[234] = M1(0,24); (*(M2[22]))[235] = M1(0,25); (*(M2[22]))[240] = M1(0,26); (*(M2[22]))[255] = M1(0,27); (*(M2[23]))[37] = M1(1,1); (*(M2[23]))[43] = M1(1,4); (*(M2[23]))[44] = M1(1,5); (*(M2[23]))[45] = M1(1,6); (*(M2[23]))[49] = M1(1,7); (*(M2[23]))[50] = M1(1,8); (*(M2[23]))[54] = M1(1,9); (*(M2[23]))[62] = M1(1,10); (*(M2[23]))[63] = M1(1,11); (*(M2[23]))[64] = M1(1,12); (*(M2[23]))[68] = M1(1,13); (*(M2[23]))[69] = M1(1,14); (*(M2[23]))[73] = M1(1,15); (*(M2[23]))[81] = M1(1,16); (*(M2[23]))[82] = M1(1,17); (*(M2[23]))[86] = M1(1,18); (*(M2[23]))[94] = M1(1,19); (*(M2[23]))[234] = M1(1,24); (*(M2[23]))[235] = M1(1,25); (*(M2[23]))[240] = M1(1,26); (*(M2[23]))[255] = M1(1,27); (*(M2[24]))[38] = M1(2,2); (*(M2[24]))[43] = M1(2,4); (*(M2[24]))[44] = M1(2,5); (*(M2[24]))[45] = M1(2,6); (*(M2[24]))[49] = M1(2,7); (*(M2[24]))[50] = M1(2,8); (*(M2[24]))[54] = M1(2,9); (*(M2[24]))[62] = M1(2,10); (*(M2[24]))[63] = M1(2,11); (*(M2[24]))[64] = M1(2,12); (*(M2[24]))[68] = M1(2,13); (*(M2[24]))[69] = M1(2,14); (*(M2[24]))[73] = M1(2,15); (*(M2[24]))[81] = M1(2,16); (*(M2[24]))[82] = M1(2,17); (*(M2[24]))[86] = M1(2,18); (*(M2[24]))[94] = M1(2,19); (*(M2[24]))[234] = M1(2,24); (*(M2[24]))[235] = M1(2,25); (*(M2[24]))[240] = M1(2,26); (*(M2[24]))[255] = M1(2,27); (*(M2[25]))[39] = M1(3,3); (*(M2[25]))[43] = M1(3,4); (*(M2[25]))[44] = M1(3,5); (*(M2[25]))[45] = M1(3,6); (*(M2[25]))[49] = M1(3,7); (*(M2[25]))[50] = M1(3,8); (*(M2[25]))[54] = M1(3,9); (*(M2[25]))[62] = M1(3,10); (*(M2[25]))[63] = M1(3,11); (*(M2[25]))[64] = M1(3,12); (*(M2[25]))[68] = M1(3,13); (*(M2[25]))[69] = M1(3,14); (*(M2[25]))[73] = M1(3,15); (*(M2[25]))[81] = M1(3,16); (*(M2[25]))[82] = M1(3,17); (*(M2[25]))[86] = M1(3,18); (*(M2[25]))[94] = M1(3,19); (*(M2[25]))[234] = M1(3,24); (*(M2[25]))[235] = M1(3,25); (*(M2[25]))[240] = M1(3,26); (*(M2[25]))[255] = M1(3,27); (*(M2[26]))[10] = M1(0,0); (*(M2[26]))[17] = M1(0,4); (*(M2[26]))[18] = M1(0,5); (*(M2[26]))[19] = M1(0,6); (*(M2[26]))[23] = M1(0,7); (*(M2[26]))[24] = M1(0,8); (*(M2[26]))[28] = M1(0,9); (*(M2[26]))[43] = M1(0,10); (*(M2[26]))[44] = M1(0,11); (*(M2[26]))[45] = M1(0,12); (*(M2[26]))[49] = M1(0,13); (*(M2[26]))[50] = M1(0,14); (*(M2[26]))[54] = M1(0,15); (*(M2[26]))[68] = M1(0,16); (*(M2[26]))[69] = M1(0,17); (*(M2[26]))[73] = M1(0,18); (*(M2[26]))[86] = M1(0,19); (*(M2[26]))[213] = M1(0,24); (*(M2[26]))[214] = M1(0,25); (*(M2[26]))[219] = M1(0,26); (*(M2[26]))[240] = M1(0,27); (*(M2[27]))[11] = M1(1,1); (*(M2[27]))[17] = M1(1,4); (*(M2[27]))[18] = M1(1,5); (*(M2[27]))[19] = M1(1,6); (*(M2[27]))[23] = M1(1,7); (*(M2[27]))[24] = M1(1,8); (*(M2[27]))[28] = M1(1,9); (*(M2[27]))[43] = M1(1,10); (*(M2[27]))[44] = M1(1,11); (*(M2[27]))[45] = M1(1,12); (*(M2[27]))[49] = M1(1,13); (*(M2[27]))[50] = M1(1,14); (*(M2[27]))[54] = M1(1,15); (*(M2[27]))[68] = M1(1,16); (*(M2[27]))[69] = M1(1,17); (*(M2[27]))[73] = M1(1,18); (*(M2[27]))[86] = M1(1,19); (*(M2[27]))[213] = M1(1,24); (*(M2[27]))[214] = M1(1,25); (*(M2[27]))[219] = M1(1,26); (*(M2[27]))[240] = M1(1,27); (*(M2[28]))[12] = M1(2,2); (*(M2[28]))[17] = M1(2,4); (*(M2[28]))[18] = M1(2,5); (*(M2[28]))[19] = M1(2,6); (*(M2[28]))[23] = M1(2,7); (*(M2[28]))[24] = M1(2,8); (*(M2[28]))[28] = M1(2,9); (*(M2[28]))[43] = M1(2,10); (*(M2[28]))[44] = M1(2,11); (*(M2[28]))[45] = M1(2,12); (*(M2[28]))[49] = M1(2,13); (*(M2[28]))[50] = M1(2,14); (*(M2[28]))[54] = M1(2,15); (*(M2[28]))[68] = M1(2,16); (*(M2[28]))[69] = M1(2,17); (*(M2[28]))[73] = M1(2,18); (*(M2[28]))[86] = M1(2,19); (*(M2[28]))[213] = M1(2,24); (*(M2[28]))[214] = M1(2,25); (*(M2[28]))[219] = M1(2,26); (*(M2[28]))[240] = M1(2,27); (*(M2[29]))[13] = M1(3,3); (*(M2[29]))[17] = M1(3,4); (*(M2[29]))[18] = M1(3,5); (*(M2[29]))[19] = M1(3,6); (*(M2[29]))[23] = M1(3,7); (*(M2[29]))[24] = M1(3,8); (*(M2[29]))[28] = M1(3,9); (*(M2[29]))[43] = M1(3,10); (*(M2[29]))[44] = M1(3,11); (*(M2[29]))[45] = M1(3,12); (*(M2[29]))[49] = M1(3,13); (*(M2[29]))[50] = M1(3,14); (*(M2[29]))[54] = M1(3,15); (*(M2[29]))[68] = M1(3,16); (*(M2[29]))[69] = M1(3,17); (*(M2[29]))[73] = M1(3,18); (*(M2[29]))[86] = M1(3,19); (*(M2[29]))[213] = M1(3,24); (*(M2[29]))[214] = M1(3,25); (*(M2[29]))[219] = M1(3,26); (*(M2[29]))[240] = M1(3,27); (*(M2[30]))[4] = M1(0,0); (*(M2[30]))[11] = M1(0,4); (*(M2[30]))[12] = M1(0,5); (*(M2[30]))[13] = M1(0,6); (*(M2[30]))[18] = M1(0,7); (*(M2[30]))[19] = M1(0,8); (*(M2[30]))[24] = M1(0,9); (*(M2[30]))[37] = M1(0,10); (*(M2[30]))[38] = M1(0,11); (*(M2[30]))[39] = M1(0,12); (*(M2[30]))[44] = M1(0,13); (*(M2[30]))[45] = M1(0,14); (*(M2[30]))[50] = M1(0,15); (*(M2[30]))[63] = M1(0,16); (*(M2[30]))[64] = M1(0,17); (*(M2[30]))[69] = M1(0,18); (*(M2[30]))[82] = M1(0,19); (*(M2[30]))[207] = M1(0,24); (*(M2[30]))[208] = M1(0,25); (*(M2[30]))[214] = M1(0,26); (*(M2[30]))[235] = M1(0,27); (*(M2[31]))[5] = M1(1,1); (*(M2[31]))[11] = M1(1,4); (*(M2[31]))[12] = M1(1,5); (*(M2[31]))[13] = M1(1,6); (*(M2[31]))[18] = M1(1,7); (*(M2[31]))[19] = M1(1,8); (*(M2[31]))[24] = M1(1,9); (*(M2[31]))[37] = M1(1,10); (*(M2[31]))[38] = M1(1,11); (*(M2[31]))[39] = M1(1,12); (*(M2[31]))[44] = M1(1,13); (*(M2[31]))[45] = M1(1,14); (*(M2[31]))[50] = M1(1,15); (*(M2[31]))[63] = M1(1,16); (*(M2[31]))[64] = M1(1,17); (*(M2[31]))[69] = M1(1,18); (*(M2[31]))[82] = M1(1,19); (*(M2[31]))[207] = M1(1,24); (*(M2[31]))[208] = M1(1,25); (*(M2[31]))[214] = M1(1,26); (*(M2[31]))[235] = M1(1,27); (*(M2[32]))[6] = M1(2,2); (*(M2[32]))[11] = M1(2,4); (*(M2[32]))[12] = M1(2,5); (*(M2[32]))[13] = M1(2,6); (*(M2[32]))[18] = M1(2,7); (*(M2[32]))[19] = M1(2,8); (*(M2[32]))[24] = M1(2,9); (*(M2[32]))[37] = M1(2,10); (*(M2[32]))[38] = M1(2,11); (*(M2[32]))[39] = M1(2,12); (*(M2[32]))[44] = M1(2,13); (*(M2[32]))[45] = M1(2,14); (*(M2[32]))[50] = M1(2,15); (*(M2[32]))[63] = M1(2,16); (*(M2[32]))[64] = M1(2,17); (*(M2[32]))[69] = M1(2,18); (*(M2[32]))[82] = M1(2,19); (*(M2[32]))[207] = M1(2,24); (*(M2[32]))[208] = M1(2,25); (*(M2[32]))[214] = M1(2,26); (*(M2[32]))[235] = M1(2,27); (*(M2[33]))[47] = M1(1,1); (*(M2[33]))[51] = M1(1,4); (*(M2[33]))[52] = M1(1,5); (*(M2[33]))[53] = M1(1,6); (*(M2[33]))[55] = M1(1,7); (*(M2[33]))[56] = M1(1,8); (*(M2[33]))[58] = M1(1,9); (*(M2[33]))[70] = M1(1,10); (*(M2[33]))[71] = M1(1,11); (*(M2[33]))[72] = M1(1,12); (*(M2[33]))[74] = M1(1,13); (*(M2[33]))[75] = M1(1,14); (*(M2[33]))[77] = M1(1,15); (*(M2[33]))[87] = M1(1,16); (*(M2[33]))[88] = M1(1,17); (*(M2[33]))[90] = M1(1,18); (*(M2[33]))[98] = M1(1,19); (*(M2[33]))[242] = M1(1,24); (*(M2[33]))[243] = M1(1,25); (*(M2[33]))[246] = M1(1,26); (*(M2[33]))[261] = M1(1,27); (*(M2[34]))[48] = M1(2,2); (*(M2[34]))[51] = M1(2,4); (*(M2[34]))[52] = M1(2,5); (*(M2[34]))[53] = M1(2,6); (*(M2[34]))[55] = M1(2,7); (*(M2[34]))[56] = M1(2,8); (*(M2[34]))[58] = M1(2,9); (*(M2[34]))[70] = M1(2,10); (*(M2[34]))[71] = M1(2,11); (*(M2[34]))[72] = M1(2,12); (*(M2[34]))[74] = M1(2,13); (*(M2[34]))[75] = M1(2,14); (*(M2[34]))[77] = M1(2,15); (*(M2[34]))[87] = M1(2,16); (*(M2[34]))[88] = M1(2,17); (*(M2[34]))[90] = M1(2,18); (*(M2[34]))[98] = M1(2,19); (*(M2[34]))[242] = M1(2,24); (*(M2[34]))[243] = M1(2,25); (*(M2[34]))[246] = M1(2,26); (*(M2[34]))[261] = M1(2,27); (*(M2[35]))[49] = M1(3,3); (*(M2[35]))[51] = M1(3,4); (*(M2[35]))[52] = M1(3,5); (*(M2[35]))[53] = M1(3,6); (*(M2[35]))[55] = M1(3,7); (*(M2[35]))[56] = M1(3,8); (*(M2[35]))[58] = M1(3,9); (*(M2[35]))[70] = M1(3,10); (*(M2[35]))[71] = M1(3,11); (*(M2[35]))[72] = M1(3,12); (*(M2[35]))[74] = M1(3,13); (*(M2[35]))[75] = M1(3,14); (*(M2[35]))[77] = M1(3,15); (*(M2[35]))[87] = M1(3,16); (*(M2[35]))[88] = M1(3,17); (*(M2[35]))[90] = M1(3,18); (*(M2[35]))[98] = M1(3,19); (*(M2[35]))[242] = M1(3,24); (*(M2[35]))[243] = M1(3,25); (*(M2[35]))[246] = M1(3,26); (*(M2[35]))[261] = M1(3,27); (*(M2[36]))[20] = M1(0,0); (*(M2[36]))[25] = M1(0,4); (*(M2[36]))[26] = M1(0,5); (*(M2[36]))[27] = M1(0,6); (*(M2[36]))[29] = M1(0,7); (*(M2[36]))[30] = M1(0,8); (*(M2[36]))[32] = M1(0,9); (*(M2[36]))[51] = M1(0,10); (*(M2[36]))[52] = M1(0,11); (*(M2[36]))[53] = M1(0,12); (*(M2[36]))[55] = M1(0,13); (*(M2[36]))[56] = M1(0,14); (*(M2[36]))[58] = M1(0,15); (*(M2[36]))[74] = M1(0,16); (*(M2[36]))[75] = M1(0,17); (*(M2[36]))[77] = M1(0,18); (*(M2[36]))[90] = M1(0,19); (*(M2[36]))[221] = M1(0,24); (*(M2[36]))[222] = M1(0,25); (*(M2[36]))[225] = M1(0,26); (*(M2[36]))[246] = M1(0,27); (*(M2[37]))[21] = M1(1,1); (*(M2[37]))[25] = M1(1,4); (*(M2[37]))[26] = M1(1,5); (*(M2[37]))[27] = M1(1,6); (*(M2[37]))[29] = M1(1,7); (*(M2[37]))[30] = M1(1,8); (*(M2[37]))[32] = M1(1,9); (*(M2[37]))[51] = M1(1,10); (*(M2[37]))[52] = M1(1,11); (*(M2[37]))[53] = M1(1,12); (*(M2[37]))[55] = M1(1,13); (*(M2[37]))[56] = M1(1,14); (*(M2[37]))[58] = M1(1,15); (*(M2[37]))[74] = M1(1,16); (*(M2[37]))[75] = M1(1,17); (*(M2[37]))[77] = M1(1,18); (*(M2[37]))[90] = M1(1,19); (*(M2[37]))[221] = M1(1,24); (*(M2[37]))[222] = M1(1,25); (*(M2[37]))[225] = M1(1,26); (*(M2[37]))[246] = M1(1,27); (*(M2[38]))[22] = M1(2,2); (*(M2[38]))[25] = M1(2,4); (*(M2[38]))[26] = M1(2,5); (*(M2[38]))[27] = M1(2,6); (*(M2[38]))[29] = M1(2,7); (*(M2[38]))[30] = M1(2,8); (*(M2[38]))[32] = M1(2,9); (*(M2[38]))[51] = M1(2,10); (*(M2[38]))[52] = M1(2,11); (*(M2[38]))[53] = M1(2,12); (*(M2[38]))[55] = M1(2,13); (*(M2[38]))[56] = M1(2,14); (*(M2[38]))[58] = M1(2,15); (*(M2[38]))[74] = M1(2,16); (*(M2[38]))[75] = M1(2,17); (*(M2[38]))[77] = M1(2,18); (*(M2[38]))[90] = M1(2,19); (*(M2[38]))[221] = M1(2,24); (*(M2[38]))[222] = M1(2,25); (*(M2[38]))[225] = M1(2,26); (*(M2[38]))[246] = M1(2,27); (*(M2[39]))[23] = M1(3,3); (*(M2[39]))[25] = M1(3,4); (*(M2[39]))[26] = M1(3,5); (*(M2[39]))[27] = M1(3,6); (*(M2[39]))[29] = M1(3,7); (*(M2[39]))[30] = M1(3,8); (*(M2[39]))[32] = M1(3,9); (*(M2[39]))[51] = M1(3,10); (*(M2[39]))[52] = M1(3,11); (*(M2[39]))[53] = M1(3,12); (*(M2[39]))[55] = M1(3,13); (*(M2[39]))[56] = M1(3,14); (*(M2[39]))[58] = M1(3,15); (*(M2[39]))[74] = M1(3,16); (*(M2[39]))[75] = M1(3,17); (*(M2[39]))[77] = M1(3,18); (*(M2[39]))[90] = M1(3,19); (*(M2[39]))[221] = M1(3,24); (*(M2[39]))[222] = M1(3,25); (*(M2[39]))[225] = M1(3,26); (*(M2[39]))[246] = M1(3,27); (*(M2[40]))[60] = M1(0,0); (*(M2[40]))[66] = M1(0,4); (*(M2[40]))[67] = M1(0,5); (*(M2[40]))[68] = M1(0,6); (*(M2[40]))[71] = M1(0,7); (*(M2[40]))[72] = M1(0,8); (*(M2[40]))[75] = M1(0,9); (*(M2[40]))[79] = M1(0,10); (*(M2[40]))[80] = M1(0,11); (*(M2[40]))[81] = M1(0,12); (*(M2[40]))[84] = M1(0,13); (*(M2[40]))[85] = M1(0,14); (*(M2[40]))[88] = M1(0,15); (*(M2[40]))[92] = M1(0,16); (*(M2[40]))[93] = M1(0,17); (*(M2[40]))[96] = M1(0,18); (*(M2[40]))[100] = M1(0,19); (*(M2[40]))[253] = M1(0,24); (*(M2[40]))[254] = M1(0,25); (*(M2[40]))[258] = M1(0,26); (*(M2[40]))[268] = M1(0,27); (*(M2[41]))[61] = M1(1,1); (*(M2[41]))[66] = M1(1,4); (*(M2[41]))[67] = M1(1,5); (*(M2[41]))[68] = M1(1,6); (*(M2[41]))[71] = M1(1,7); (*(M2[41]))[72] = M1(1,8); (*(M2[41]))[75] = M1(1,9); (*(M2[41]))[79] = M1(1,10); (*(M2[41]))[80] = M1(1,11); (*(M2[41]))[81] = M1(1,12); (*(M2[41]))[84] = M1(1,13); (*(M2[41]))[85] = M1(1,14); (*(M2[41]))[88] = M1(1,15); (*(M2[41]))[92] = M1(1,16); (*(M2[41]))[93] = M1(1,17); (*(M2[41]))[96] = M1(1,18); (*(M2[41]))[100] = M1(1,19); (*(M2[41]))[253] = M1(1,24); (*(M2[41]))[254] = M1(1,25); (*(M2[41]))[258] = M1(1,26); (*(M2[41]))[268] = M1(1,27); (*(M2[42]))[62] = M1(2,2); (*(M2[42]))[66] = M1(2,4); (*(M2[42]))[67] = M1(2,5); (*(M2[42]))[68] = M1(2,6); (*(M2[42]))[71] = M1(2,7); (*(M2[42]))[72] = M1(2,8); (*(M2[42]))[75] = M1(2,9); (*(M2[42]))[79] = M1(2,10); (*(M2[42]))[80] = M1(2,11); (*(M2[42]))[81] = M1(2,12); (*(M2[42]))[84] = M1(2,13); (*(M2[42]))[85] = M1(2,14); (*(M2[42]))[88] = M1(2,15); (*(M2[42]))[92] = M1(2,16); (*(M2[42]))[93] = M1(2,17); (*(M2[42]))[96] = M1(2,18); (*(M2[42]))[100] = M1(2,19); (*(M2[42]))[253] = M1(2,24); (*(M2[42]))[254] = M1(2,25); (*(M2[42]))[258] = M1(2,26); (*(M2[42]))[268] = M1(2,27); (*(M2[43]))[63] = M1(3,3); (*(M2[43]))[66] = M1(3,4); (*(M2[43]))[67] = M1(3,5); (*(M2[43]))[68] = M1(3,6); (*(M2[43]))[71] = M1(3,7); (*(M2[43]))[72] = M1(3,8); (*(M2[43]))[75] = M1(3,9); (*(M2[43]))[79] = M1(3,10); (*(M2[43]))[80] = M1(3,11); (*(M2[43]))[81] = M1(3,12); (*(M2[43]))[84] = M1(3,13); (*(M2[43]))[85] = M1(3,14); (*(M2[43]))[88] = M1(3,15); (*(M2[43]))[92] = M1(3,16); (*(M2[43]))[93] = M1(3,17); (*(M2[43]))[96] = M1(3,18); (*(M2[43]))[100] = M1(3,19); (*(M2[43]))[253] = M1(3,24); (*(M2[43]))[254] = M1(3,25); (*(M2[43]))[258] = M1(3,26); (*(M2[43]))[268] = M1(3,27); (*(M2[44]))[161] = M1(4,20); (*(M2[44]))[163] = M1(4,21); (*(M2[44]))[172] = M1(4,22); (*(M2[44]))[193] = M1(4,23); (*(M2[44]))[322] = M1(4,28); (*(M2[45]))[41] = M1(0,0); (*(M2[45]))[47] = M1(0,4); (*(M2[45]))[48] = M1(0,5); (*(M2[45]))[49] = M1(0,6); (*(M2[45]))[52] = M1(0,7); (*(M2[45]))[53] = M1(0,8); (*(M2[45]))[56] = M1(0,9); (*(M2[45]))[66] = M1(0,10); (*(M2[45]))[67] = M1(0,11); (*(M2[45]))[68] = M1(0,12); (*(M2[45]))[71] = M1(0,13); (*(M2[45]))[72] = M1(0,14); (*(M2[45]))[75] = M1(0,15); (*(M2[45]))[84] = M1(0,16); (*(M2[45]))[85] = M1(0,17); (*(M2[45]))[88] = M1(0,18); (*(M2[45]))[96] = M1(0,19); (*(M2[45]))[238] = M1(0,24); (*(M2[45]))[239] = M1(0,25); (*(M2[45]))[243] = M1(0,26); (*(M2[45]))[258] = M1(0,27); (*(M2[46]))[42] = M1(1,1); (*(M2[46]))[47] = M1(1,4); (*(M2[46]))[48] = M1(1,5); (*(M2[46]))[49] = M1(1,6); (*(M2[46]))[52] = M1(1,7); (*(M2[46]))[53] = M1(1,8); (*(M2[46]))[56] = M1(1,9); (*(M2[46]))[66] = M1(1,10); (*(M2[46]))[67] = M1(1,11); (*(M2[46]))[68] = M1(1,12); (*(M2[46]))[71] = M1(1,13); (*(M2[46]))[72] = M1(1,14); (*(M2[46]))[75] = M1(1,15); (*(M2[46]))[84] = M1(1,16); (*(M2[46]))[85] = M1(1,17); (*(M2[46]))[88] = M1(1,18); (*(M2[46]))[96] = M1(1,19); (*(M2[46]))[238] = M1(1,24); (*(M2[46]))[239] = M1(1,25); (*(M2[46]))[243] = M1(1,26); (*(M2[46]))[258] = M1(1,27); (*(M2[47]))[43] = M1(2,2); (*(M2[47]))[47] = M1(2,4); (*(M2[47]))[48] = M1(2,5); (*(M2[47]))[49] = M1(2,6); (*(M2[47]))[52] = M1(2,7); (*(M2[47]))[53] = M1(2,8); (*(M2[47]))[56] = M1(2,9); (*(M2[47]))[66] = M1(2,10); (*(M2[47]))[67] = M1(2,11); (*(M2[47]))[68] = M1(2,12); (*(M2[47]))[71] = M1(2,13); (*(M2[47]))[72] = M1(2,14); (*(M2[47]))[75] = M1(2,15); (*(M2[47]))[84] = M1(2,16); (*(M2[47]))[85] = M1(2,17); (*(M2[47]))[88] = M1(2,18); (*(M2[47]))[96] = M1(2,19); (*(M2[47]))[238] = M1(2,24); (*(M2[47]))[239] = M1(2,25); (*(M2[47]))[243] = M1(2,26); (*(M2[47]))[258] = M1(2,27); (*(M2[48]))[44] = M1(3,3); (*(M2[48]))[47] = M1(3,4); (*(M2[48]))[48] = M1(3,5); (*(M2[48]))[49] = M1(3,6); (*(M2[48]))[52] = M1(3,7); (*(M2[48]))[53] = M1(3,8); (*(M2[48]))[56] = M1(3,9); (*(M2[48]))[66] = M1(3,10); (*(M2[48]))[67] = M1(3,11); (*(M2[48]))[68] = M1(3,12); (*(M2[48]))[71] = M1(3,13); (*(M2[48]))[72] = M1(3,14); (*(M2[48]))[75] = M1(3,15); (*(M2[48]))[84] = M1(3,16); (*(M2[48]))[85] = M1(3,17); (*(M2[48]))[88] = M1(3,18); (*(M2[48]))[96] = M1(3,19); (*(M2[48]))[238] = M1(3,24); (*(M2[48]))[239] = M1(3,25); (*(M2[48]))[243] = M1(3,26); (*(M2[48]))[258] = M1(3,27); (*(M2[49]))[142] = M1(4,20); (*(M2[49]))[144] = M1(4,21); (*(M2[49]))[153] = M1(4,22); (*(M2[49]))[185] = M1(4,23); (*(M2[49]))[312] = M1(4,28); (*(M2[50]))[15] = M1(0,0); (*(M2[50]))[21] = M1(0,4); (*(M2[50]))[22] = M1(0,5); (*(M2[50]))[23] = M1(0,6); (*(M2[50]))[26] = M1(0,7); (*(M2[50]))[27] = M1(0,8); (*(M2[50]))[30] = M1(0,9); (*(M2[50]))[47] = M1(0,10); (*(M2[50]))[48] = M1(0,11); (*(M2[50]))[49] = M1(0,12); (*(M2[50]))[52] = M1(0,13); (*(M2[50]))[53] = M1(0,14); (*(M2[50]))[56] = M1(0,15); (*(M2[50]))[71] = M1(0,16); (*(M2[50]))[72] = M1(0,17); (*(M2[50]))[75] = M1(0,18); (*(M2[50]))[88] = M1(0,19); (*(M2[50]))[217] = M1(0,24); (*(M2[50]))[218] = M1(0,25); (*(M2[50]))[222] = M1(0,26); (*(M2[50]))[243] = M1(0,27); (*(M2[51]))[16] = M1(1,1); (*(M2[51]))[21] = M1(1,4); (*(M2[51]))[22] = M1(1,5); (*(M2[51]))[23] = M1(1,6); (*(M2[51]))[26] = M1(1,7); (*(M2[51]))[27] = M1(1,8); (*(M2[51]))[30] = M1(1,9); (*(M2[51]))[47] = M1(1,10); (*(M2[51]))[48] = M1(1,11); (*(M2[51]))[49] = M1(1,12); (*(M2[51]))[52] = M1(1,13); (*(M2[51]))[53] = M1(1,14); (*(M2[51]))[56] = M1(1,15); (*(M2[51]))[71] = M1(1,16); (*(M2[51]))[72] = M1(1,17); (*(M2[51]))[75] = M1(1,18); (*(M2[51]))[88] = M1(1,19); (*(M2[51]))[217] = M1(1,24); (*(M2[51]))[218] = M1(1,25); (*(M2[51]))[222] = M1(1,26); (*(M2[51]))[243] = M1(1,27); (*(M2[52]))[17] = M1(2,2); (*(M2[52]))[21] = M1(2,4); (*(M2[52]))[22] = M1(2,5); (*(M2[52]))[23] = M1(2,6); (*(M2[52]))[26] = M1(2,7); (*(M2[52]))[27] = M1(2,8); (*(M2[52]))[30] = M1(2,9); (*(M2[52]))[47] = M1(2,10); (*(M2[52]))[48] = M1(2,11); (*(M2[52]))[49] = M1(2,12); (*(M2[52]))[52] = M1(2,13); (*(M2[52]))[53] = M1(2,14); (*(M2[52]))[56] = M1(2,15); (*(M2[52]))[71] = M1(2,16); (*(M2[52]))[72] = M1(2,17); (*(M2[52]))[75] = M1(2,18); (*(M2[52]))[88] = M1(2,19); (*(M2[52]))[217] = M1(2,24); (*(M2[52]))[218] = M1(2,25); (*(M2[52]))[222] = M1(2,26); (*(M2[52]))[243] = M1(2,27); (*(M2[53]))[18] = M1(3,3); (*(M2[53]))[21] = M1(3,4); (*(M2[53]))[22] = M1(3,5); (*(M2[53]))[23] = M1(3,6); (*(M2[53]))[26] = M1(3,7); (*(M2[53]))[27] = M1(3,8); (*(M2[53]))[30] = M1(3,9); (*(M2[53]))[47] = M1(3,10); (*(M2[53]))[48] = M1(3,11); (*(M2[53]))[49] = M1(3,12); (*(M2[53]))[52] = M1(3,13); (*(M2[53]))[53] = M1(3,14); (*(M2[53]))[56] = M1(3,15); (*(M2[53]))[71] = M1(3,16); (*(M2[53]))[72] = M1(3,17); (*(M2[53]))[75] = M1(3,18); (*(M2[53]))[88] = M1(3,19); (*(M2[53]))[217] = M1(3,24); (*(M2[53]))[218] = M1(3,25); (*(M2[53]))[222] = M1(3,26); (*(M2[53]))[243] = M1(3,27); (*(M2[54]))[116] = M1(4,20); (*(M2[54]))[118] = M1(4,21); (*(M2[54]))[127] = M1(4,22); (*(M2[54]))[172] = M1(4,23); (*(M2[54]))[297] = M1(4,28); (*(M2[55]))[35] = M1(0,0); (*(M2[55]))[42] = M1(0,4); (*(M2[55]))[43] = M1(0,5); (*(M2[55]))[44] = M1(0,6); (*(M2[55]))[48] = M1(0,7); (*(M2[55]))[49] = M1(0,8); (*(M2[55]))[53] = M1(0,9); (*(M2[55]))[61] = M1(0,10); (*(M2[55]))[62] = M1(0,11); (*(M2[55]))[63] = M1(0,12); (*(M2[55]))[67] = M1(0,13); (*(M2[55]))[68] = M1(0,14); (*(M2[55]))[72] = M1(0,15); (*(M2[55]))[80] = M1(0,16); (*(M2[55]))[81] = M1(0,17); (*(M2[55]))[85] = M1(0,18); (*(M2[55]))[93] = M1(0,19); (*(M2[55]))[233] = M1(0,24); (*(M2[55]))[234] = M1(0,25); (*(M2[55]))[239] = M1(0,26); (*(M2[55]))[254] = M1(0,27); (*(M2[56]))[36] = M1(1,1); (*(M2[56]))[42] = M1(1,4); (*(M2[56]))[43] = M1(1,5); (*(M2[56]))[44] = M1(1,6); (*(M2[56]))[48] = M1(1,7); (*(M2[56]))[49] = M1(1,8); (*(M2[56]))[53] = M1(1,9); (*(M2[56]))[61] = M1(1,10); (*(M2[56]))[62] = M1(1,11); (*(M2[56]))[63] = M1(1,12); (*(M2[56]))[67] = M1(1,13); (*(M2[56]))[68] = M1(1,14); (*(M2[56]))[72] = M1(1,15); (*(M2[56]))[80] = M1(1,16); (*(M2[56]))[81] = M1(1,17); (*(M2[56]))[85] = M1(1,18); (*(M2[56]))[93] = M1(1,19); (*(M2[56]))[233] = M1(1,24); (*(M2[56]))[234] = M1(1,25); (*(M2[56]))[239] = M1(1,26); (*(M2[56]))[254] = M1(1,27); (*(M2[57]))[37] = M1(2,2); (*(M2[57]))[42] = M1(2,4); (*(M2[57]))[43] = M1(2,5); (*(M2[57]))[44] = M1(2,6); (*(M2[57]))[48] = M1(2,7); (*(M2[57]))[49] = M1(2,8); (*(M2[57]))[53] = M1(2,9); (*(M2[57]))[61] = M1(2,10); (*(M2[57]))[62] = M1(2,11); (*(M2[57]))[63] = M1(2,12); (*(M2[57]))[67] = M1(2,13); (*(M2[57]))[68] = M1(2,14); (*(M2[57]))[72] = M1(2,15); (*(M2[57]))[80] = M1(2,16); (*(M2[57]))[81] = M1(2,17); (*(M2[57]))[85] = M1(2,18); (*(M2[57]))[93] = M1(2,19); (*(M2[57]))[233] = M1(2,24); (*(M2[57]))[234] = M1(2,25); (*(M2[57]))[239] = M1(2,26); (*(M2[57]))[254] = M1(2,27); (*(M2[58]))[38] = M1(3,3); (*(M2[58]))[42] = M1(3,4); (*(M2[58]))[43] = M1(3,5); (*(M2[58]))[44] = M1(3,6); (*(M2[58]))[48] = M1(3,7); (*(M2[58]))[49] = M1(3,8); (*(M2[58]))[53] = M1(3,9); (*(M2[58]))[61] = M1(3,10); (*(M2[58]))[62] = M1(3,11); (*(M2[58]))[63] = M1(3,12); (*(M2[58]))[67] = M1(3,13); (*(M2[58]))[68] = M1(3,14); (*(M2[58]))[72] = M1(3,15); (*(M2[58]))[80] = M1(3,16); (*(M2[58]))[81] = M1(3,17); (*(M2[58]))[85] = M1(3,18); (*(M2[58]))[93] = M1(3,19); (*(M2[58]))[233] = M1(3,24); (*(M2[58]))[234] = M1(3,25); (*(M2[58]))[239] = M1(3,26); (*(M2[58]))[254] = M1(3,27); (*(M2[59]))[136] = M1(4,20); (*(M2[59]))[138] = M1(4,21); (*(M2[59]))[149] = M1(4,22); (*(M2[59]))[181] = M1(4,23); (*(M2[59]))[308] = M1(4,28); (*(M2[60]))[9] = M1(0,0); (*(M2[60]))[16] = M1(0,4); (*(M2[60]))[17] = M1(0,5); (*(M2[60]))[18] = M1(0,6); (*(M2[60]))[22] = M1(0,7); (*(M2[60]))[23] = M1(0,8); (*(M2[60]))[27] = M1(0,9); (*(M2[60]))[42] = M1(0,10); (*(M2[60]))[43] = M1(0,11); (*(M2[60]))[44] = M1(0,12); (*(M2[60]))[48] = M1(0,13); (*(M2[60]))[49] = M1(0,14); (*(M2[60]))[53] = M1(0,15); (*(M2[60]))[67] = M1(0,16); (*(M2[60]))[68] = M1(0,17); (*(M2[60]))[72] = M1(0,18); (*(M2[60]))[85] = M1(0,19); (*(M2[60]))[212] = M1(0,24); (*(M2[60]))[213] = M1(0,25); (*(M2[60]))[218] = M1(0,26); (*(M2[60]))[239] = M1(0,27); (*(M2[61]))[10] = M1(1,1); (*(M2[61]))[16] = M1(1,4); (*(M2[61]))[17] = M1(1,5); (*(M2[61]))[18] = M1(1,6); (*(M2[61]))[22] = M1(1,7); (*(M2[61]))[23] = M1(1,8); (*(M2[61]))[27] = M1(1,9); (*(M2[61]))[42] = M1(1,10); (*(M2[61]))[43] = M1(1,11); (*(M2[61]))[44] = M1(1,12); (*(M2[61]))[48] = M1(1,13); (*(M2[61]))[49] = M1(1,14); (*(M2[61]))[53] = M1(1,15); (*(M2[61]))[67] = M1(1,16); (*(M2[61]))[68] = M1(1,17); (*(M2[61]))[72] = M1(1,18); (*(M2[61]))[85] = M1(1,19); (*(M2[61]))[212] = M1(1,24); (*(M2[61]))[213] = M1(1,25); (*(M2[61]))[218] = M1(1,26); (*(M2[61]))[239] = M1(1,27); (*(M2[62]))[11] = M1(2,2); (*(M2[62]))[16] = M1(2,4); (*(M2[62]))[17] = M1(2,5); (*(M2[62]))[18] = M1(2,6); (*(M2[62]))[22] = M1(2,7); (*(M2[62]))[23] = M1(2,8); (*(M2[62]))[27] = M1(2,9); (*(M2[62]))[42] = M1(2,10); (*(M2[62]))[43] = M1(2,11); (*(M2[62]))[44] = M1(2,12); (*(M2[62]))[48] = M1(2,13); (*(M2[62]))[49] = M1(2,14); (*(M2[62]))[53] = M1(2,15); (*(M2[62]))[67] = M1(2,16); (*(M2[62]))[68] = M1(2,17); (*(M2[62]))[72] = M1(2,18); (*(M2[62]))[85] = M1(2,19); (*(M2[62]))[212] = M1(2,24); (*(M2[62]))[213] = M1(2,25); (*(M2[62]))[218] = M1(2,26); (*(M2[62]))[239] = M1(2,27); (*(M2[63]))[12] = M1(3,3); (*(M2[63]))[16] = M1(3,4); (*(M2[63]))[17] = M1(3,5); (*(M2[63]))[18] = M1(3,6); (*(M2[63]))[22] = M1(3,7); (*(M2[63]))[23] = M1(3,8); (*(M2[63]))[27] = M1(3,9); (*(M2[63]))[42] = M1(3,10); (*(M2[63]))[43] = M1(3,11); (*(M2[63]))[44] = M1(3,12); (*(M2[63]))[48] = M1(3,13); (*(M2[63]))[49] = M1(3,14); (*(M2[63]))[53] = M1(3,15); (*(M2[63]))[67] = M1(3,16); (*(M2[63]))[68] = M1(3,17); (*(M2[63]))[72] = M1(3,18); (*(M2[63]))[85] = M1(3,19); (*(M2[63]))[212] = M1(3,24); (*(M2[63]))[213] = M1(3,25); (*(M2[63]))[218] = M1(3,26); (*(M2[63]))[239] = M1(3,27); (*(M2[64]))[110] = M1(4,20); (*(M2[64]))[112] = M1(4,21); (*(M2[64]))[123] = M1(4,22); (*(M2[64]))[168] = M1(4,23); (*(M2[64]))[293] = M1(4,28); (*(M2[65]))[3] = M1(0,0); (*(M2[65]))[10] = M1(0,4); (*(M2[65]))[11] = M1(0,5); (*(M2[65]))[12] = M1(0,6); (*(M2[65]))[17] = M1(0,7); (*(M2[65]))[18] = M1(0,8); (*(M2[65]))[23] = M1(0,9); (*(M2[65]))[36] = M1(0,10); (*(M2[65]))[37] = M1(0,11); (*(M2[65]))[38] = M1(0,12); (*(M2[65]))[43] = M1(0,13); (*(M2[65]))[44] = M1(0,14); (*(M2[65]))[49] = M1(0,15); (*(M2[65]))[62] = M1(0,16); (*(M2[65]))[63] = M1(0,17); (*(M2[65]))[68] = M1(0,18); (*(M2[65]))[81] = M1(0,19); (*(M2[65]))[206] = M1(0,24); (*(M2[65]))[207] = M1(0,25); (*(M2[65]))[213] = M1(0,26); (*(M2[65]))[234] = M1(0,27); (*(M2[66]))[4] = M1(1,1); (*(M2[66]))[10] = M1(1,4); (*(M2[66]))[11] = M1(1,5); (*(M2[66]))[12] = M1(1,6); (*(M2[66]))[17] = M1(1,7); (*(M2[66]))[18] = M1(1,8); (*(M2[66]))[23] = M1(1,9); (*(M2[66]))[36] = M1(1,10); (*(M2[66]))[37] = M1(1,11); (*(M2[66]))[38] = M1(1,12); (*(M2[66]))[43] = M1(1,13); (*(M2[66]))[44] = M1(1,14); (*(M2[66]))[49] = M1(1,15); (*(M2[66]))[62] = M1(1,16); (*(M2[66]))[63] = M1(1,17); (*(M2[66]))[68] = M1(1,18); (*(M2[66]))[81] = M1(1,19); (*(M2[66]))[206] = M1(1,24); (*(M2[66]))[207] = M1(1,25); (*(M2[66]))[213] = M1(1,26); (*(M2[66]))[234] = M1(1,27); (*(M2[67]))[5] = M1(2,2); (*(M2[67]))[10] = M1(2,4); (*(M2[67]))[11] = M1(2,5); (*(M2[67]))[12] = M1(2,6); (*(M2[67]))[17] = M1(2,7); (*(M2[67]))[18] = M1(2,8); (*(M2[67]))[23] = M1(2,9); (*(M2[67]))[36] = M1(2,10); (*(M2[67]))[37] = M1(2,11); (*(M2[67]))[38] = M1(2,12); (*(M2[67]))[43] = M1(2,13); (*(M2[67]))[44] = M1(2,14); (*(M2[67]))[49] = M1(2,15); (*(M2[67]))[62] = M1(2,16); (*(M2[67]))[63] = M1(2,17); (*(M2[67]))[68] = M1(2,18); (*(M2[67]))[81] = M1(2,19); (*(M2[67]))[206] = M1(2,24); (*(M2[67]))[207] = M1(2,25); (*(M2[67]))[213] = M1(2,26); (*(M2[67]))[234] = M1(2,27); (*(M2[68]))[6] = M1(3,3); (*(M2[68]))[10] = M1(3,4); (*(M2[68]))[11] = M1(3,5); (*(M2[68]))[12] = M1(3,6); (*(M2[68]))[17] = M1(3,7); (*(M2[68]))[18] = M1(3,8); (*(M2[68]))[23] = M1(3,9); (*(M2[68]))[36] = M1(3,10); (*(M2[68]))[37] = M1(3,11); (*(M2[68]))[38] = M1(3,12); (*(M2[68]))[43] = M1(3,13); (*(M2[68]))[44] = M1(3,14); (*(M2[68]))[49] = M1(3,15); (*(M2[68]))[62] = M1(3,16); (*(M2[68]))[63] = M1(3,17); (*(M2[68]))[68] = M1(3,18); (*(M2[68]))[81] = M1(3,19); (*(M2[68]))[206] = M1(3,24); (*(M2[68]))[207] = M1(3,25); (*(M2[68]))[213] = M1(3,26); (*(M2[68]))[234] = M1(3,27); (*(M2[69]))[104] = M1(4,20); (*(M2[69]))[106] = M1(4,21); (*(M2[69]))[118] = M1(4,22); (*(M2[69]))[163] = M1(4,23); (*(M2[69]))[288] = M1(4,28); (*(M2[70]))[59] = M1(0,0); (*(M2[70]))[65] = M1(0,4); (*(M2[70]))[66] = M1(0,5); (*(M2[70]))[67] = M1(0,6); (*(M2[70]))[70] = M1(0,7); (*(M2[70]))[71] = M1(0,8); (*(M2[70]))[74] = M1(0,9); (*(M2[70]))[78] = M1(0,10); (*(M2[70]))[79] = M1(0,11); (*(M2[70]))[80] = M1(0,12); (*(M2[70]))[83] = M1(0,13); (*(M2[70]))[84] = M1(0,14); (*(M2[70]))[87] = M1(0,15); (*(M2[70]))[91] = M1(0,16); (*(M2[70]))[92] = M1(0,17); (*(M2[70]))[95] = M1(0,18); (*(M2[70]))[99] = M1(0,19); (*(M2[70]))[252] = M1(0,24); (*(M2[70]))[253] = M1(0,25); (*(M2[70]))[257] = M1(0,26); (*(M2[70]))[267] = M1(0,27); (*(M2[71]))[60] = M1(1,1); (*(M2[71]))[65] = M1(1,4); (*(M2[71]))[66] = M1(1,5); (*(M2[71]))[67] = M1(1,6); (*(M2[71]))[70] = M1(1,7); (*(M2[71]))[71] = M1(1,8); (*(M2[71]))[74] = M1(1,9); (*(M2[71]))[78] = M1(1,10); (*(M2[71]))[79] = M1(1,11); (*(M2[71]))[80] = M1(1,12); (*(M2[71]))[83] = M1(1,13); (*(M2[71]))[84] = M1(1,14); (*(M2[71]))[87] = M1(1,15); (*(M2[71]))[91] = M1(1,16); (*(M2[71]))[92] = M1(1,17); (*(M2[71]))[95] = M1(1,18); (*(M2[71]))[99] = M1(1,19); (*(M2[71]))[252] = M1(1,24); (*(M2[71]))[253] = M1(1,25); (*(M2[71]))[257] = M1(1,26); (*(M2[71]))[267] = M1(1,27); (*(M2[72]))[61] = M1(2,2); (*(M2[72]))[65] = M1(2,4); (*(M2[72]))[66] = M1(2,5); (*(M2[72]))[67] = M1(2,6); (*(M2[72]))[70] = M1(2,7); (*(M2[72]))[71] = M1(2,8); (*(M2[72]))[74] = M1(2,9); (*(M2[72]))[78] = M1(2,10); (*(M2[72]))[79] = M1(2,11); (*(M2[72]))[80] = M1(2,12); (*(M2[72]))[83] = M1(2,13); (*(M2[72]))[84] = M1(2,14); (*(M2[72]))[87] = M1(2,15); (*(M2[72]))[91] = M1(2,16); (*(M2[72]))[92] = M1(2,17); (*(M2[72]))[95] = M1(2,18); (*(M2[72]))[99] = M1(2,19); (*(M2[72]))[252] = M1(2,24); (*(M2[72]))[253] = M1(2,25); (*(M2[72]))[257] = M1(2,26); (*(M2[72]))[267] = M1(2,27); (*(M2[73]))[62] = M1(3,3); (*(M2[73]))[65] = M1(3,4); (*(M2[73]))[66] = M1(3,5); (*(M2[73]))[67] = M1(3,6); (*(M2[73]))[70] = M1(3,7); (*(M2[73]))[71] = M1(3,8); (*(M2[73]))[74] = M1(3,9); (*(M2[73]))[78] = M1(3,10); (*(M2[73]))[79] = M1(3,11); (*(M2[73]))[80] = M1(3,12); (*(M2[73]))[83] = M1(3,13); (*(M2[73]))[84] = M1(3,14); (*(M2[73]))[87] = M1(3,15); (*(M2[73]))[91] = M1(3,16); (*(M2[73]))[92] = M1(3,17); (*(M2[73]))[95] = M1(3,18); (*(M2[73]))[99] = M1(3,19); (*(M2[73]))[252] = M1(3,24); (*(M2[73]))[253] = M1(3,25); (*(M2[73]))[257] = M1(3,26); (*(M2[73]))[267] = M1(3,27); (*(M2[74]))[160] = M1(4,20); (*(M2[74]))[162] = M1(4,21); (*(M2[74]))[171] = M1(4,22); (*(M2[74]))[192] = M1(4,23); (*(M2[74]))[321] = M1(4,28); (*(M2[75]))[40] = M1(0,0); (*(M2[75]))[46] = M1(0,4); (*(M2[75]))[47] = M1(0,5); (*(M2[75]))[48] = M1(0,6); (*(M2[75]))[51] = M1(0,7); (*(M2[75]))[52] = M1(0,8); (*(M2[75]))[55] = M1(0,9); (*(M2[75]))[65] = M1(0,10); (*(M2[75]))[66] = M1(0,11); (*(M2[75]))[67] = M1(0,12); (*(M2[75]))[70] = M1(0,13); (*(M2[75]))[71] = M1(0,14); (*(M2[75]))[74] = M1(0,15); (*(M2[75]))[83] = M1(0,16); (*(M2[75]))[84] = M1(0,17); (*(M2[75]))[87] = M1(0,18); (*(M2[75]))[95] = M1(0,19); (*(M2[75]))[237] = M1(0,24); (*(M2[75]))[238] = M1(0,25); (*(M2[75]))[242] = M1(0,26); (*(M2[75]))[257] = M1(0,27); (*(M2[76]))[41] = M1(1,1); (*(M2[76]))[46] = M1(1,4); (*(M2[76]))[47] = M1(1,5); (*(M2[76]))[48] = M1(1,6); (*(M2[76]))[51] = M1(1,7); (*(M2[76]))[52] = M1(1,8); (*(M2[76]))[55] = M1(1,9); (*(M2[76]))[65] = M1(1,10); (*(M2[76]))[66] = M1(1,11); (*(M2[76]))[67] = M1(1,12); (*(M2[76]))[70] = M1(1,13); (*(M2[76]))[71] = M1(1,14); (*(M2[76]))[74] = M1(1,15); (*(M2[76]))[83] = M1(1,16); (*(M2[76]))[84] = M1(1,17); (*(M2[76]))[87] = M1(1,18); (*(M2[76]))[95] = M1(1,19); (*(M2[76]))[237] = M1(1,24); (*(M2[76]))[238] = M1(1,25); (*(M2[76]))[242] = M1(1,26); (*(M2[76]))[257] = M1(1,27); (*(M2[77]))[42] = M1(2,2); (*(M2[77]))[46] = M1(2,4); (*(M2[77]))[47] = M1(2,5); (*(M2[77]))[48] = M1(2,6); (*(M2[77]))[51] = M1(2,7); (*(M2[77]))[52] = M1(2,8); (*(M2[77]))[55] = M1(2,9); (*(M2[77]))[65] = M1(2,10); (*(M2[77]))[66] = M1(2,11); (*(M2[77]))[67] = M1(2,12); (*(M2[77]))[70] = M1(2,13); (*(M2[77]))[71] = M1(2,14); (*(M2[77]))[74] = M1(2,15); (*(M2[77]))[83] = M1(2,16); (*(M2[77]))[84] = M1(2,17); (*(M2[77]))[87] = M1(2,18); (*(M2[77]))[95] = M1(2,19); (*(M2[77]))[237] = M1(2,24); (*(M2[77]))[238] = M1(2,25); (*(M2[77]))[242] = M1(2,26); (*(M2[77]))[257] = M1(2,27); (*(M2[78]))[43] = M1(3,3); (*(M2[78]))[46] = M1(3,4); (*(M2[78]))[47] = M1(3,5); (*(M2[78]))[48] = M1(3,6); (*(M2[78]))[51] = M1(3,7); (*(M2[78]))[52] = M1(3,8); (*(M2[78]))[55] = M1(3,9); (*(M2[78]))[65] = M1(3,10); (*(M2[78]))[66] = M1(3,11); (*(M2[78]))[67] = M1(3,12); (*(M2[78]))[70] = M1(3,13); (*(M2[78]))[71] = M1(3,14); (*(M2[78]))[74] = M1(3,15); (*(M2[78]))[83] = M1(3,16); (*(M2[78]))[84] = M1(3,17); (*(M2[78]))[87] = M1(3,18); (*(M2[78]))[95] = M1(3,19); (*(M2[78]))[237] = M1(3,24); (*(M2[78]))[238] = M1(3,25); (*(M2[78]))[242] = M1(3,26); (*(M2[78]))[257] = M1(3,27); (*(M2[79]))[141] = M1(4,20); (*(M2[79]))[143] = M1(4,21); (*(M2[79]))[152] = M1(4,22); (*(M2[79]))[184] = M1(4,23); (*(M2[79]))[311] = M1(4,28); (*(M2[80]))[14] = M1(0,0); (*(M2[80]))[20] = M1(0,4); (*(M2[80]))[21] = M1(0,5); (*(M2[80]))[22] = M1(0,6); (*(M2[80]))[25] = M1(0,7); (*(M2[80]))[26] = M1(0,8); (*(M2[80]))[29] = M1(0,9); (*(M2[80]))[46] = M1(0,10); (*(M2[80]))[47] = M1(0,11); (*(M2[80]))[48] = M1(0,12); (*(M2[80]))[51] = M1(0,13); (*(M2[80]))[52] = M1(0,14); (*(M2[80]))[55] = M1(0,15); (*(M2[80]))[70] = M1(0,16); (*(M2[80]))[71] = M1(0,17); (*(M2[80]))[74] = M1(0,18); (*(M2[80]))[87] = M1(0,19); (*(M2[80]))[216] = M1(0,24); (*(M2[80]))[217] = M1(0,25); (*(M2[80]))[221] = M1(0,26); (*(M2[80]))[242] = M1(0,27); (*(M2[81]))[15] = M1(1,1); (*(M2[81]))[20] = M1(1,4); (*(M2[81]))[21] = M1(1,5); (*(M2[81]))[22] = M1(1,6); (*(M2[81]))[25] = M1(1,7); (*(M2[81]))[26] = M1(1,8); (*(M2[81]))[29] = M1(1,9); (*(M2[81]))[46] = M1(1,10); (*(M2[81]))[47] = M1(1,11); (*(M2[81]))[48] = M1(1,12); (*(M2[81]))[51] = M1(1,13); (*(M2[81]))[52] = M1(1,14); (*(M2[81]))[55] = M1(1,15); (*(M2[81]))[70] = M1(1,16); (*(M2[81]))[71] = M1(1,17); (*(M2[81]))[74] = M1(1,18); (*(M2[81]))[87] = M1(1,19); (*(M2[81]))[216] = M1(1,24); (*(M2[81]))[217] = M1(1,25); (*(M2[81]))[221] = M1(1,26); (*(M2[81]))[242] = M1(1,27); (*(M2[82]))[16] = M1(2,2); (*(M2[82]))[20] = M1(2,4); (*(M2[82]))[21] = M1(2,5); (*(M2[82]))[22] = M1(2,6); (*(M2[82]))[25] = M1(2,7); (*(M2[82]))[26] = M1(2,8); (*(M2[82]))[29] = M1(2,9); (*(M2[82]))[46] = M1(2,10); (*(M2[82]))[47] = M1(2,11); (*(M2[82]))[48] = M1(2,12); (*(M2[82]))[51] = M1(2,13); (*(M2[82]))[52] = M1(2,14); (*(M2[82]))[55] = M1(2,15); (*(M2[82]))[70] = M1(2,16); (*(M2[82]))[71] = M1(2,17); (*(M2[82]))[74] = M1(2,18); (*(M2[82]))[87] = M1(2,19); (*(M2[82]))[216] = M1(2,24); (*(M2[82]))[217] = M1(2,25); (*(M2[82]))[221] = M1(2,26); (*(M2[82]))[242] = M1(2,27); (*(M2[83]))[17] = M1(3,3); (*(M2[83]))[20] = M1(3,4); (*(M2[83]))[21] = M1(3,5); (*(M2[83]))[22] = M1(3,6); (*(M2[83]))[25] = M1(3,7); (*(M2[83]))[26] = M1(3,8); (*(M2[83]))[29] = M1(3,9); (*(M2[83]))[46] = M1(3,10); (*(M2[83]))[47] = M1(3,11); (*(M2[83]))[48] = M1(3,12); (*(M2[83]))[51] = M1(3,13); (*(M2[83]))[52] = M1(3,14); (*(M2[83]))[55] = M1(3,15); (*(M2[83]))[70] = M1(3,16); (*(M2[83]))[71] = M1(3,17); (*(M2[83]))[74] = M1(3,18); (*(M2[83]))[87] = M1(3,19); (*(M2[83]))[216] = M1(3,24); (*(M2[83]))[217] = M1(3,25); (*(M2[83]))[221] = M1(3,26); (*(M2[83]))[242] = M1(3,27); (*(M2[84]))[115] = M1(4,20); (*(M2[84]))[117] = M1(4,21); (*(M2[84]))[126] = M1(4,22); (*(M2[84]))[171] = M1(4,23); (*(M2[84]))[296] = M1(4,28); (*(M2[85]))[34] = M1(0,0); (*(M2[85]))[41] = M1(0,4); (*(M2[85]))[42] = M1(0,5); (*(M2[85]))[43] = M1(0,6); (*(M2[85]))[47] = M1(0,7); (*(M2[85]))[48] = M1(0,8); (*(M2[85]))[52] = M1(0,9); (*(M2[85]))[60] = M1(0,10); (*(M2[85]))[61] = M1(0,11); (*(M2[85]))[62] = M1(0,12); (*(M2[85]))[66] = M1(0,13); (*(M2[85]))[67] = M1(0,14); (*(M2[85]))[71] = M1(0,15); (*(M2[85]))[79] = M1(0,16); (*(M2[85]))[80] = M1(0,17); (*(M2[85]))[84] = M1(0,18); (*(M2[85]))[92] = M1(0,19); (*(M2[85]))[232] = M1(0,24); (*(M2[85]))[233] = M1(0,25); (*(M2[85]))[238] = M1(0,26); (*(M2[85]))[253] = M1(0,27); (*(M2[86]))[35] = M1(1,1); (*(M2[86]))[41] = M1(1,4); (*(M2[86]))[42] = M1(1,5); (*(M2[86]))[43] = M1(1,6); (*(M2[86]))[47] = M1(1,7); (*(M2[86]))[48] = M1(1,8); (*(M2[86]))[52] = M1(1,9); (*(M2[86]))[60] = M1(1,10); (*(M2[86]))[61] = M1(1,11); (*(M2[86]))[62] = M1(1,12); (*(M2[86]))[66] = M1(1,13); (*(M2[86]))[67] = M1(1,14); (*(M2[86]))[71] = M1(1,15); (*(M2[86]))[79] = M1(1,16); (*(M2[86]))[80] = M1(1,17); (*(M2[86]))[84] = M1(1,18); (*(M2[86]))[92] = M1(1,19); (*(M2[86]))[232] = M1(1,24); (*(M2[86]))[233] = M1(1,25); (*(M2[86]))[238] = M1(1,26); (*(M2[86]))[253] = M1(1,27); (*(M2[87]))[36] = M1(2,2); (*(M2[87]))[41] = M1(2,4); (*(M2[87]))[42] = M1(2,5); (*(M2[87]))[43] = M1(2,6); (*(M2[87]))[47] = M1(2,7); (*(M2[87]))[48] = M1(2,8); (*(M2[87]))[52] = M1(2,9); (*(M2[87]))[60] = M1(2,10); (*(M2[87]))[61] = M1(2,11); (*(M2[87]))[62] = M1(2,12); (*(M2[87]))[66] = M1(2,13); (*(M2[87]))[67] = M1(2,14); (*(M2[87]))[71] = M1(2,15); (*(M2[87]))[79] = M1(2,16); (*(M2[87]))[80] = M1(2,17); (*(M2[87]))[84] = M1(2,18); (*(M2[87]))[92] = M1(2,19); (*(M2[87]))[232] = M1(2,24); (*(M2[87]))[233] = M1(2,25); (*(M2[87]))[238] = M1(2,26); (*(M2[87]))[253] = M1(2,27); (*(M2[88]))[37] = M1(3,3); (*(M2[88]))[41] = M1(3,4); (*(M2[88]))[42] = M1(3,5); (*(M2[88]))[43] = M1(3,6); (*(M2[88]))[47] = M1(3,7); (*(M2[88]))[48] = M1(3,8); (*(M2[88]))[52] = M1(3,9); (*(M2[88]))[60] = M1(3,10); (*(M2[88]))[61] = M1(3,11); (*(M2[88]))[62] = M1(3,12); (*(M2[88]))[66] = M1(3,13); (*(M2[88]))[67] = M1(3,14); (*(M2[88]))[71] = M1(3,15); (*(M2[88]))[79] = M1(3,16); (*(M2[88]))[80] = M1(3,17); (*(M2[88]))[84] = M1(3,18); (*(M2[88]))[92] = M1(3,19); (*(M2[88]))[232] = M1(3,24); (*(M2[88]))[233] = M1(3,25); (*(M2[88]))[238] = M1(3,26); (*(M2[88]))[253] = M1(3,27); (*(M2[89]))[135] = M1(4,20); (*(M2[89]))[137] = M1(4,21); (*(M2[89]))[148] = M1(4,22); (*(M2[89]))[180] = M1(4,23); (*(M2[89]))[307] = M1(4,28); (*(M2[90]))[8] = M1(0,0); (*(M2[90]))[15] = M1(0,4); (*(M2[90]))[16] = M1(0,5); (*(M2[90]))[17] = M1(0,6); (*(M2[90]))[21] = M1(0,7); (*(M2[90]))[22] = M1(0,8); (*(M2[90]))[26] = M1(0,9); (*(M2[90]))[41] = M1(0,10); (*(M2[90]))[42] = M1(0,11); (*(M2[90]))[43] = M1(0,12); (*(M2[90]))[47] = M1(0,13); (*(M2[90]))[48] = M1(0,14); (*(M2[90]))[52] = M1(0,15); (*(M2[90]))[66] = M1(0,16); (*(M2[90]))[67] = M1(0,17); (*(M2[90]))[71] = M1(0,18); (*(M2[90]))[84] = M1(0,19); (*(M2[90]))[211] = M1(0,24); (*(M2[90]))[212] = M1(0,25); (*(M2[90]))[217] = M1(0,26); (*(M2[90]))[238] = M1(0,27); (*(M2[91]))[9] = M1(1,1); (*(M2[91]))[15] = M1(1,4); (*(M2[91]))[16] = M1(1,5); (*(M2[91]))[17] = M1(1,6); (*(M2[91]))[21] = M1(1,7); (*(M2[91]))[22] = M1(1,8); (*(M2[91]))[26] = M1(1,9); (*(M2[91]))[41] = M1(1,10); (*(M2[91]))[42] = M1(1,11); (*(M2[91]))[43] = M1(1,12); (*(M2[91]))[47] = M1(1,13); (*(M2[91]))[48] = M1(1,14); (*(M2[91]))[52] = M1(1,15); (*(M2[91]))[66] = M1(1,16); (*(M2[91]))[67] = M1(1,17); (*(M2[91]))[71] = M1(1,18); (*(M2[91]))[84] = M1(1,19); (*(M2[91]))[211] = M1(1,24); (*(M2[91]))[212] = M1(1,25); (*(M2[91]))[217] = M1(1,26); (*(M2[91]))[238] = M1(1,27); (*(M2[92]))[10] = M1(2,2); (*(M2[92]))[15] = M1(2,4); (*(M2[92]))[16] = M1(2,5); (*(M2[92]))[17] = M1(2,6); (*(M2[92]))[21] = M1(2,7); (*(M2[92]))[22] = M1(2,8); (*(M2[92]))[26] = M1(2,9); (*(M2[92]))[41] = M1(2,10); (*(M2[92]))[42] = M1(2,11); (*(M2[92]))[43] = M1(2,12); (*(M2[92]))[47] = M1(2,13); (*(M2[92]))[48] = M1(2,14); (*(M2[92]))[52] = M1(2,15); (*(M2[92]))[66] = M1(2,16); (*(M2[92]))[67] = M1(2,17); (*(M2[92]))[71] = M1(2,18); (*(M2[92]))[84] = M1(2,19); (*(M2[92]))[211] = M1(2,24); (*(M2[92]))[212] = M1(2,25); (*(M2[92]))[217] = M1(2,26); (*(M2[92]))[238] = M1(2,27); (*(M2[93]))[11] = M1(3,3); (*(M2[93]))[15] = M1(3,4); (*(M2[93]))[16] = M1(3,5); (*(M2[93]))[17] = M1(3,6); (*(M2[93]))[21] = M1(3,7); (*(M2[93]))[22] = M1(3,8); (*(M2[93]))[26] = M1(3,9); (*(M2[93]))[41] = M1(3,10); (*(M2[93]))[42] = M1(3,11); (*(M2[93]))[43] = M1(3,12); (*(M2[93]))[47] = M1(3,13); (*(M2[93]))[48] = M1(3,14); (*(M2[93]))[52] = M1(3,15); (*(M2[93]))[66] = M1(3,16); (*(M2[93]))[67] = M1(3,17); (*(M2[93]))[71] = M1(3,18); (*(M2[93]))[84] = M1(3,19); (*(M2[93]))[211] = M1(3,24); (*(M2[93]))[212] = M1(3,25); (*(M2[93]))[217] = M1(3,26); (*(M2[93]))[238] = M1(3,27); (*(M2[94]))[109] = M1(4,20); (*(M2[94]))[111] = M1(4,21); (*(M2[94]))[122] = M1(4,22); (*(M2[94]))[167] = M1(4,23); (*(M2[94]))[292] = M1(4,28); (*(M2[95]))[2] = M1(0,0); (*(M2[95]))[9] = M1(0,4); (*(M2[95]))[10] = M1(0,5); (*(M2[95]))[11] = M1(0,6); (*(M2[95]))[16] = M1(0,7); (*(M2[95]))[17] = M1(0,8); (*(M2[95]))[22] = M1(0,9); (*(M2[95]))[35] = M1(0,10); (*(M2[95]))[36] = M1(0,11); (*(M2[95]))[37] = M1(0,12); (*(M2[95]))[42] = M1(0,13); (*(M2[95]))[43] = M1(0,14); (*(M2[95]))[48] = M1(0,15); (*(M2[95]))[61] = M1(0,16); (*(M2[95]))[62] = M1(0,17); (*(M2[95]))[67] = M1(0,18); (*(M2[95]))[80] = M1(0,19); (*(M2[95]))[205] = M1(0,24); (*(M2[95]))[206] = M1(0,25); (*(M2[95]))[212] = M1(0,26); (*(M2[95]))[233] = M1(0,27); (*(M2[96]))[3] = M1(1,1); (*(M2[96]))[9] = M1(1,4); (*(M2[96]))[10] = M1(1,5); (*(M2[96]))[11] = M1(1,6); (*(M2[96]))[16] = M1(1,7); (*(M2[96]))[17] = M1(1,8); (*(M2[96]))[22] = M1(1,9); (*(M2[96]))[35] = M1(1,10); (*(M2[96]))[36] = M1(1,11); (*(M2[96]))[37] = M1(1,12); (*(M2[96]))[42] = M1(1,13); (*(M2[96]))[43] = M1(1,14); (*(M2[96]))[48] = M1(1,15); (*(M2[96]))[61] = M1(1,16); (*(M2[96]))[62] = M1(1,17); (*(M2[96]))[67] = M1(1,18); (*(M2[96]))[80] = M1(1,19); (*(M2[96]))[205] = M1(1,24); (*(M2[96]))[206] = M1(1,25); (*(M2[96]))[212] = M1(1,26); (*(M2[96]))[233] = M1(1,27); (*(M2[97]))[4] = M1(2,2); (*(M2[97]))[9] = M1(2,4); (*(M2[97]))[10] = M1(2,5); (*(M2[97]))[11] = M1(2,6); (*(M2[97]))[16] = M1(2,7); (*(M2[97]))[17] = M1(2,8); (*(M2[97]))[22] = M1(2,9); (*(M2[97]))[35] = M1(2,10); (*(M2[97]))[36] = M1(2,11); (*(M2[97]))[37] = M1(2,12); (*(M2[97]))[42] = M1(2,13); (*(M2[97]))[43] = M1(2,14); (*(M2[97]))[48] = M1(2,15); (*(M2[97]))[61] = M1(2,16); (*(M2[97]))[62] = M1(2,17); (*(M2[97]))[67] = M1(2,18); (*(M2[97]))[80] = M1(2,19); (*(M2[97]))[205] = M1(2,24); (*(M2[97]))[206] = M1(2,25); (*(M2[97]))[212] = M1(2,26); (*(M2[97]))[233] = M1(2,27); (*(M2[98]))[5] = M1(3,3); (*(M2[98]))[9] = M1(3,4); (*(M2[98]))[10] = M1(3,5); (*(M2[98]))[11] = M1(3,6); (*(M2[98]))[16] = M1(3,7); (*(M2[98]))[17] = M1(3,8); (*(M2[98]))[22] = M1(3,9); (*(M2[98]))[35] = M1(3,10); (*(M2[98]))[36] = M1(3,11); (*(M2[98]))[37] = M1(3,12); (*(M2[98]))[42] = M1(3,13); (*(M2[98]))[43] = M1(3,14); (*(M2[98]))[48] = M1(3,15); (*(M2[98]))[61] = M1(3,16); (*(M2[98]))[62] = M1(3,17); (*(M2[98]))[67] = M1(3,18); (*(M2[98]))[80] = M1(3,19); (*(M2[98]))[205] = M1(3,24); (*(M2[98]))[206] = M1(3,25); (*(M2[98]))[212] = M1(3,26); (*(M2[98]))[233] = M1(3,27); (*(M2[99]))[103] = M1(4,20); (*(M2[99]))[105] = M1(4,21); (*(M2[99]))[117] = M1(4,22); (*(M2[99]))[162] = M1(4,23); (*(M2[99]))[287] = M1(4,28); (*(M2[100]))[33] = M1(0,0); (*(M2[100]))[40] = M1(0,4); (*(M2[100]))[41] = M1(0,5); (*(M2[100]))[42] = M1(0,6); (*(M2[100]))[46] = M1(0,7); (*(M2[100]))[47] = M1(0,8); (*(M2[100]))[51] = M1(0,9); (*(M2[100]))[59] = M1(0,10); (*(M2[100]))[60] = M1(0,11); (*(M2[100]))[61] = M1(0,12); (*(M2[100]))[65] = M1(0,13); (*(M2[100]))[66] = M1(0,14); (*(M2[100]))[70] = M1(0,15); (*(M2[100]))[78] = M1(0,16); (*(M2[100]))[79] = M1(0,17); (*(M2[100]))[83] = M1(0,18); (*(M2[100]))[91] = M1(0,19); (*(M2[100]))[231] = M1(0,24); (*(M2[100]))[232] = M1(0,25); (*(M2[100]))[237] = M1(0,26); (*(M2[100]))[252] = M1(0,27); (*(M2[101]))[34] = M1(1,1); (*(M2[101]))[40] = M1(1,4); (*(M2[101]))[41] = M1(1,5); (*(M2[101]))[42] = M1(1,6); (*(M2[101]))[46] = M1(1,7); (*(M2[101]))[47] = M1(1,8); (*(M2[101]))[51] = M1(1,9); (*(M2[101]))[59] = M1(1,10); (*(M2[101]))[60] = M1(1,11); (*(M2[101]))[61] = M1(1,12); (*(M2[101]))[65] = M1(1,13); (*(M2[101]))[66] = M1(1,14); (*(M2[101]))[70] = M1(1,15); (*(M2[101]))[78] = M1(1,16); (*(M2[101]))[79] = M1(1,17); (*(M2[101]))[83] = M1(1,18); (*(M2[101]))[91] = M1(1,19); (*(M2[101]))[231] = M1(1,24); (*(M2[101]))[232] = M1(1,25); (*(M2[101]))[237] = M1(1,26); (*(M2[101]))[252] = M1(1,27); (*(M2[102]))[35] = M1(2,2); (*(M2[102]))[40] = M1(2,4); (*(M2[102]))[41] = M1(2,5); (*(M2[102]))[42] = M1(2,6); (*(M2[102]))[46] = M1(2,7); (*(M2[102]))[47] = M1(2,8); (*(M2[102]))[51] = M1(2,9); (*(M2[102]))[59] = M1(2,10); (*(M2[102]))[60] = M1(2,11); (*(M2[102]))[61] = M1(2,12); (*(M2[102]))[65] = M1(2,13); (*(M2[102]))[66] = M1(2,14); (*(M2[102]))[70] = M1(2,15); (*(M2[102]))[78] = M1(2,16); (*(M2[102]))[79] = M1(2,17); (*(M2[102]))[83] = M1(2,18); (*(M2[102]))[91] = M1(2,19); (*(M2[102]))[231] = M1(2,24); (*(M2[102]))[232] = M1(2,25); (*(M2[102]))[237] = M1(2,26); (*(M2[102]))[252] = M1(2,27); (*(M2[103]))[36] = M1(3,3); (*(M2[103]))[40] = M1(3,4); (*(M2[103]))[41] = M1(3,5); (*(M2[103]))[42] = M1(3,6); (*(M2[103]))[46] = M1(3,7); (*(M2[103]))[47] = M1(3,8); (*(M2[103]))[51] = M1(3,9); (*(M2[103]))[59] = M1(3,10); (*(M2[103]))[60] = M1(3,11); (*(M2[103]))[61] = M1(3,12); (*(M2[103]))[65] = M1(3,13); (*(M2[103]))[66] = M1(3,14); (*(M2[103]))[70] = M1(3,15); (*(M2[103]))[78] = M1(3,16); (*(M2[103]))[79] = M1(3,17); (*(M2[103]))[83] = M1(3,18); (*(M2[103]))[91] = M1(3,19); (*(M2[103]))[231] = M1(3,24); (*(M2[103]))[232] = M1(3,25); (*(M2[103]))[237] = M1(3,26); (*(M2[103]))[252] = M1(3,27); (*(M2[104]))[134] = M1(4,20); (*(M2[104]))[136] = M1(4,21); (*(M2[104]))[147] = M1(4,22); (*(M2[104]))[179] = M1(4,23); (*(M2[104]))[306] = M1(4,28); (*(M2[105]))[7] = M1(0,0); (*(M2[105]))[14] = M1(0,4); (*(M2[105]))[15] = M1(0,5); (*(M2[105]))[16] = M1(0,6); (*(M2[105]))[20] = M1(0,7); (*(M2[105]))[21] = M1(0,8); (*(M2[105]))[25] = M1(0,9); (*(M2[105]))[40] = M1(0,10); (*(M2[105]))[41] = M1(0,11); (*(M2[105]))[42] = M1(0,12); (*(M2[105]))[46] = M1(0,13); (*(M2[105]))[47] = M1(0,14); (*(M2[105]))[51] = M1(0,15); (*(M2[105]))[65] = M1(0,16); (*(M2[105]))[66] = M1(0,17); (*(M2[105]))[70] = M1(0,18); (*(M2[105]))[83] = M1(0,19); (*(M2[105]))[210] = M1(0,24); (*(M2[105]))[211] = M1(0,25); (*(M2[105]))[216] = M1(0,26); (*(M2[105]))[237] = M1(0,27); (*(M2[106]))[8] = M1(1,1); (*(M2[106]))[14] = M1(1,4); (*(M2[106]))[15] = M1(1,5); (*(M2[106]))[16] = M1(1,6); (*(M2[106]))[20] = M1(1,7); (*(M2[106]))[21] = M1(1,8); (*(M2[106]))[25] = M1(1,9); (*(M2[106]))[40] = M1(1,10); (*(M2[106]))[41] = M1(1,11); (*(M2[106]))[42] = M1(1,12); (*(M2[106]))[46] = M1(1,13); (*(M2[106]))[47] = M1(1,14); (*(M2[106]))[51] = M1(1,15); (*(M2[106]))[65] = M1(1,16); (*(M2[106]))[66] = M1(1,17); (*(M2[106]))[70] = M1(1,18); (*(M2[106]))[83] = M1(1,19); (*(M2[106]))[210] = M1(1,24); (*(M2[106]))[211] = M1(1,25); (*(M2[106]))[216] = M1(1,26); (*(M2[106]))[237] = M1(1,27); (*(M2[107]))[9] = M1(2,2); (*(M2[107]))[14] = M1(2,4); (*(M2[107]))[15] = M1(2,5); (*(M2[107]))[16] = M1(2,6); (*(M2[107]))[20] = M1(2,7); (*(M2[107]))[21] = M1(2,8); (*(M2[107]))[25] = M1(2,9); (*(M2[107]))[40] = M1(2,10); (*(M2[107]))[41] = M1(2,11); (*(M2[107]))[42] = M1(2,12); (*(M2[107]))[46] = M1(2,13); (*(M2[107]))[47] = M1(2,14); (*(M2[107]))[51] = M1(2,15); (*(M2[107]))[65] = M1(2,16); (*(M2[107]))[66] = M1(2,17); (*(M2[107]))[70] = M1(2,18); (*(M2[107]))[83] = M1(2,19); (*(M2[107]))[210] = M1(2,24); (*(M2[107]))[211] = M1(2,25); (*(M2[107]))[216] = M1(2,26); (*(M2[107]))[237] = M1(2,27); (*(M2[108]))[10] = M1(3,3); (*(M2[108]))[14] = M1(3,4); (*(M2[108]))[15] = M1(3,5); (*(M2[108]))[16] = M1(3,6); (*(M2[108]))[20] = M1(3,7); (*(M2[108]))[21] = M1(3,8); (*(M2[108]))[25] = M1(3,9); (*(M2[108]))[40] = M1(3,10); (*(M2[108]))[41] = M1(3,11); (*(M2[108]))[42] = M1(3,12); (*(M2[108]))[46] = M1(3,13); (*(M2[108]))[47] = M1(3,14); (*(M2[108]))[51] = M1(3,15); (*(M2[108]))[65] = M1(3,16); (*(M2[108]))[66] = M1(3,17); (*(M2[108]))[70] = M1(3,18); (*(M2[108]))[83] = M1(3,19); (*(M2[108]))[210] = M1(3,24); (*(M2[108]))[211] = M1(3,25); (*(M2[108]))[216] = M1(3,26); (*(M2[108]))[237] = M1(3,27); (*(M2[109]))[108] = M1(4,20); (*(M2[109]))[110] = M1(4,21); (*(M2[109]))[121] = M1(4,22); (*(M2[109]))[166] = M1(4,23); (*(M2[109]))[291] = M1(4,28); (*(M2[110]))[1] = M1(0,0); (*(M2[110]))[8] = M1(0,4); (*(M2[110]))[9] = M1(0,5); (*(M2[110]))[10] = M1(0,6); (*(M2[110]))[15] = M1(0,7); (*(M2[110]))[16] = M1(0,8); (*(M2[110]))[21] = M1(0,9); (*(M2[110]))[34] = M1(0,10); (*(M2[110]))[35] = M1(0,11); (*(M2[110]))[36] = M1(0,12); (*(M2[110]))[41] = M1(0,13); (*(M2[110]))[42] = M1(0,14); (*(M2[110]))[47] = M1(0,15); (*(M2[110]))[60] = M1(0,16); (*(M2[110]))[61] = M1(0,17); (*(M2[110]))[66] = M1(0,18); (*(M2[110]))[79] = M1(0,19); (*(M2[110]))[204] = M1(0,24); (*(M2[110]))[205] = M1(0,25); (*(M2[110]))[211] = M1(0,26); (*(M2[110]))[232] = M1(0,27); (*(M2[111]))[2] = M1(1,1); (*(M2[111]))[8] = M1(1,4); (*(M2[111]))[9] = M1(1,5); (*(M2[111]))[10] = M1(1,6); (*(M2[111]))[15] = M1(1,7); (*(M2[111]))[16] = M1(1,8); (*(M2[111]))[21] = M1(1,9); (*(M2[111]))[34] = M1(1,10); (*(M2[111]))[35] = M1(1,11); (*(M2[111]))[36] = M1(1,12); (*(M2[111]))[41] = M1(1,13); (*(M2[111]))[42] = M1(1,14); (*(M2[111]))[47] = M1(1,15); (*(M2[111]))[60] = M1(1,16); (*(M2[111]))[61] = M1(1,17); (*(M2[111]))[66] = M1(1,18); (*(M2[111]))[79] = M1(1,19); (*(M2[111]))[204] = M1(1,24); (*(M2[111]))[205] = M1(1,25); (*(M2[111]))[211] = M1(1,26); (*(M2[111]))[232] = M1(1,27); (*(M2[112]))[3] = M1(2,2); (*(M2[112]))[8] = M1(2,4); (*(M2[112]))[9] = M1(2,5); (*(M2[112]))[10] = M1(2,6); (*(M2[112]))[15] = M1(2,7); (*(M2[112]))[16] = M1(2,8); (*(M2[112]))[21] = M1(2,9); (*(M2[112]))[34] = M1(2,10); (*(M2[112]))[35] = M1(2,11); (*(M2[112]))[36] = M1(2,12); (*(M2[112]))[41] = M1(2,13); (*(M2[112]))[42] = M1(2,14); (*(M2[112]))[47] = M1(2,15); (*(M2[112]))[60] = M1(2,16); (*(M2[112]))[61] = M1(2,17); (*(M2[112]))[66] = M1(2,18); (*(M2[112]))[79] = M1(2,19); (*(M2[112]))[204] = M1(2,24); (*(M2[112]))[205] = M1(2,25); (*(M2[112]))[211] = M1(2,26); (*(M2[112]))[232] = M1(2,27); (*(M2[113]))[4] = M1(3,3); (*(M2[113]))[8] = M1(3,4); (*(M2[113]))[9] = M1(3,5); (*(M2[113]))[10] = M1(3,6); (*(M2[113]))[15] = M1(3,7); (*(M2[113]))[16] = M1(3,8); (*(M2[113]))[21] = M1(3,9); (*(M2[113]))[34] = M1(3,10); (*(M2[113]))[35] = M1(3,11); (*(M2[113]))[36] = M1(3,12); (*(M2[113]))[41] = M1(3,13); (*(M2[113]))[42] = M1(3,14); (*(M2[113]))[47] = M1(3,15); (*(M2[113]))[60] = M1(3,16); (*(M2[113]))[61] = M1(3,17); (*(M2[113]))[66] = M1(3,18); (*(M2[113]))[79] = M1(3,19); (*(M2[113]))[204] = M1(3,24); (*(M2[113]))[205] = M1(3,25); (*(M2[113]))[211] = M1(3,26); (*(M2[113]))[232] = M1(3,27); (*(M2[114]))[102] = M1(4,20); (*(M2[114]))[104] = M1(4,21); (*(M2[114]))[116] = M1(4,22); (*(M2[114]))[161] = M1(4,23); (*(M2[114]))[286] = M1(4,28); (*(M2[115]))[0] = M1(0,0); (*(M2[115]))[7] = M1(0,4); (*(M2[115]))[8] = M1(0,5); (*(M2[115]))[9] = M1(0,6); (*(M2[115]))[14] = M1(0,7); (*(M2[115]))[15] = M1(0,8); (*(M2[115]))[20] = M1(0,9); (*(M2[115]))[33] = M1(0,10); (*(M2[115]))[34] = M1(0,11); (*(M2[115]))[35] = M1(0,12); (*(M2[115]))[40] = M1(0,13); (*(M2[115]))[41] = M1(0,14); (*(M2[115]))[46] = M1(0,15); (*(M2[115]))[59] = M1(0,16); (*(M2[115]))[60] = M1(0,17); (*(M2[115]))[65] = M1(0,18); (*(M2[115]))[78] = M1(0,19); (*(M2[115]))[203] = M1(0,24); (*(M2[115]))[204] = M1(0,25); (*(M2[115]))[210] = M1(0,26); (*(M2[115]))[231] = M1(0,27); (*(M2[116]))[1] = M1(1,1); (*(M2[116]))[7] = M1(1,4); (*(M2[116]))[8] = M1(1,5); (*(M2[116]))[9] = M1(1,6); (*(M2[116]))[14] = M1(1,7); (*(M2[116]))[15] = M1(1,8); (*(M2[116]))[20] = M1(1,9); (*(M2[116]))[33] = M1(1,10); (*(M2[116]))[34] = M1(1,11); (*(M2[116]))[35] = M1(1,12); (*(M2[116]))[40] = M1(1,13); (*(M2[116]))[41] = M1(1,14); (*(M2[116]))[46] = M1(1,15); (*(M2[116]))[59] = M1(1,16); (*(M2[116]))[60] = M1(1,17); (*(M2[116]))[65] = M1(1,18); (*(M2[116]))[78] = M1(1,19); (*(M2[116]))[203] = M1(1,24); (*(M2[116]))[204] = M1(1,25); (*(M2[116]))[210] = M1(1,26); (*(M2[116]))[231] = M1(1,27); (*(M2[117]))[2] = M1(2,2); (*(M2[117]))[7] = M1(2,4); (*(M2[117]))[8] = M1(2,5); (*(M2[117]))[9] = M1(2,6); (*(M2[117]))[14] = M1(2,7); (*(M2[117]))[15] = M1(2,8); (*(M2[117]))[20] = M1(2,9); (*(M2[117]))[33] = M1(2,10); (*(M2[117]))[34] = M1(2,11); (*(M2[117]))[35] = M1(2,12); (*(M2[117]))[40] = M1(2,13); (*(M2[117]))[41] = M1(2,14); (*(M2[117]))[46] = M1(2,15); (*(M2[117]))[59] = M1(2,16); (*(M2[117]))[60] = M1(2,17); (*(M2[117]))[65] = M1(2,18); (*(M2[117]))[78] = M1(2,19); (*(M2[117]))[203] = M1(2,24); (*(M2[117]))[204] = M1(2,25); (*(M2[117]))[210] = M1(2,26); (*(M2[117]))[231] = M1(2,27); (*(M2[118]))[3] = M1(3,3); (*(M2[118]))[7] = M1(3,4); (*(M2[118]))[8] = M1(3,5); (*(M2[118]))[9] = M1(3,6); (*(M2[118]))[14] = M1(3,7); (*(M2[118]))[15] = M1(3,8); (*(M2[118]))[20] = M1(3,9); (*(M2[118]))[33] = M1(3,10); (*(M2[118]))[34] = M1(3,11); (*(M2[118]))[35] = M1(3,12); (*(M2[118]))[40] = M1(3,13); (*(M2[118]))[41] = M1(3,14); (*(M2[118]))[46] = M1(3,15); (*(M2[118]))[59] = M1(3,16); (*(M2[118]))[60] = M1(3,17); (*(M2[118]))[65] = M1(3,18); (*(M2[118]))[78] = M1(3,19); (*(M2[118]))[203] = M1(3,24); (*(M2[118]))[204] = M1(3,25); (*(M2[118]))[210] = M1(3,26); (*(M2[118]))[231] = M1(3,27); (*(M2[119]))[101] = M1(4,20); (*(M2[119]))[103] = M1(4,21); (*(M2[119]))[115] = M1(4,22); (*(M2[119]))[160] = M1(4,23); (*(M2[119]))[285] = M1(4,28); (*(M2[120]))[162] = M1(0,0); (*(M2[120]))[168] = M1(0,4); (*(M2[120]))[169] = M1(0,5); (*(M2[120]))[170] = M1(0,6); (*(M2[120]))[173] = M1(0,7); (*(M2[120]))[174] = M1(0,8); (*(M2[120]))[177] = M1(0,9); (*(M2[120]))[181] = M1(0,10); (*(M2[120]))[182] = M1(0,11); (*(M2[120]))[183] = M1(0,12); (*(M2[120]))[186] = M1(0,13); (*(M2[120]))[187] = M1(0,14); (*(M2[120]))[190] = M1(0,15); (*(M2[120]))[194] = M1(0,16); (*(M2[120]))[195] = M1(0,17); (*(M2[120]))[198] = M1(0,18); (*(M2[120]))[202] = M1(0,19); (*(M2[120]))[323] = M1(0,24); (*(M2[120]))[324] = M1(0,25); (*(M2[120]))[327] = M1(0,26); (*(M2[120]))[333] = M1(0,27); (*(M2[121]))[163] = M1(1,1); (*(M2[121]))[168] = M1(1,4); (*(M2[121]))[169] = M1(1,5); (*(M2[121]))[170] = M1(1,6); (*(M2[121]))[173] = M1(1,7); (*(M2[121]))[174] = M1(1,8); (*(M2[121]))[177] = M1(1,9); (*(M2[121]))[181] = M1(1,10); (*(M2[121]))[182] = M1(1,11); (*(M2[121]))[183] = M1(1,12); (*(M2[121]))[186] = M1(1,13); (*(M2[121]))[187] = M1(1,14); (*(M2[121]))[190] = M1(1,15); (*(M2[121]))[194] = M1(1,16); (*(M2[121]))[195] = M1(1,17); (*(M2[121]))[198] = M1(1,18); (*(M2[121]))[202] = M1(1,19); (*(M2[121]))[323] = M1(1,24); (*(M2[121]))[324] = M1(1,25); (*(M2[121]))[327] = M1(1,26); (*(M2[121]))[333] = M1(1,27); (*(M2[122]))[164] = M1(2,2); (*(M2[122]))[168] = M1(2,4); (*(M2[122]))[169] = M1(2,5); (*(M2[122]))[170] = M1(2,6); (*(M2[122]))[173] = M1(2,7); (*(M2[122]))[174] = M1(2,8); (*(M2[122]))[177] = M1(2,9); (*(M2[122]))[181] = M1(2,10); (*(M2[122]))[182] = M1(2,11); (*(M2[122]))[183] = M1(2,12); (*(M2[122]))[186] = M1(2,13); (*(M2[122]))[187] = M1(2,14); (*(M2[122]))[190] = M1(2,15); (*(M2[122]))[194] = M1(2,16); (*(M2[122]))[195] = M1(2,17); (*(M2[122]))[198] = M1(2,18); (*(M2[122]))[202] = M1(2,19); (*(M2[122]))[323] = M1(2,24); (*(M2[122]))[324] = M1(2,25); (*(M2[122]))[327] = M1(2,26); (*(M2[122]))[333] = M1(2,27); (*(M2[123]))[165] = M1(3,3); (*(M2[123]))[168] = M1(3,4); (*(M2[123]))[169] = M1(3,5); (*(M2[123]))[170] = M1(3,6); (*(M2[123]))[173] = M1(3,7); (*(M2[123]))[174] = M1(3,8); (*(M2[123]))[177] = M1(3,9); (*(M2[123]))[181] = M1(3,10); (*(M2[123]))[182] = M1(3,11); (*(M2[123]))[183] = M1(3,12); (*(M2[123]))[186] = M1(3,13); (*(M2[123]))[187] = M1(3,14); (*(M2[123]))[190] = M1(3,15); (*(M2[123]))[194] = M1(3,16); (*(M2[123]))[195] = M1(3,17); (*(M2[123]))[198] = M1(3,18); (*(M2[123]))[202] = M1(3,19); (*(M2[123]))[323] = M1(3,24); (*(M2[123]))[324] = M1(3,25); (*(M2[123]))[327] = M1(3,26); (*(M2[123]))[333] = M1(3,27); (*(M2[124]))[143] = M1(0,0); (*(M2[124]))[149] = M1(0,4); (*(M2[124]))[150] = M1(0,5); (*(M2[124]))[151] = M1(0,6); (*(M2[124]))[154] = M1(0,7); (*(M2[124]))[155] = M1(0,8); (*(M2[124]))[158] = M1(0,9); (*(M2[124]))[168] = M1(0,10); (*(M2[124]))[169] = M1(0,11); (*(M2[124]))[170] = M1(0,12); (*(M2[124]))[173] = M1(0,13); (*(M2[124]))[174] = M1(0,14); (*(M2[124]))[177] = M1(0,15); (*(M2[124]))[186] = M1(0,16); (*(M2[124]))[187] = M1(0,17); (*(M2[124]))[190] = M1(0,18); (*(M2[124]))[198] = M1(0,19); (*(M2[124]))[313] = M1(0,24); (*(M2[124]))[314] = M1(0,25); (*(M2[124]))[317] = M1(0,26); (*(M2[124]))[327] = M1(0,27); (*(M2[125]))[144] = M1(1,1); (*(M2[125]))[149] = M1(1,4); (*(M2[125]))[150] = M1(1,5); (*(M2[125]))[151] = M1(1,6); (*(M2[125]))[154] = M1(1,7); (*(M2[125]))[155] = M1(1,8); (*(M2[125]))[158] = M1(1,9); (*(M2[125]))[168] = M1(1,10); (*(M2[125]))[169] = M1(1,11); (*(M2[125]))[170] = M1(1,12); (*(M2[125]))[173] = M1(1,13); (*(M2[125]))[174] = M1(1,14); (*(M2[125]))[177] = M1(1,15); (*(M2[125]))[186] = M1(1,16); (*(M2[125]))[187] = M1(1,17); (*(M2[125]))[190] = M1(1,18); (*(M2[125]))[198] = M1(1,19); (*(M2[125]))[313] = M1(1,24); (*(M2[125]))[314] = M1(1,25); (*(M2[125]))[317] = M1(1,26); (*(M2[125]))[327] = M1(1,27); (*(M2[126]))[145] = M1(2,2); (*(M2[126]))[149] = M1(2,4); (*(M2[126]))[150] = M1(2,5); (*(M2[126]))[151] = M1(2,6); (*(M2[126]))[154] = M1(2,7); (*(M2[126]))[155] = M1(2,8); (*(M2[126]))[158] = M1(2,9); (*(M2[126]))[168] = M1(2,10); (*(M2[126]))[169] = M1(2,11); (*(M2[126]))[170] = M1(2,12); (*(M2[126]))[173] = M1(2,13); (*(M2[126]))[174] = M1(2,14); (*(M2[126]))[177] = M1(2,15); (*(M2[126]))[186] = M1(2,16); (*(M2[126]))[187] = M1(2,17); (*(M2[126]))[190] = M1(2,18); (*(M2[126]))[198] = M1(2,19); (*(M2[126]))[313] = M1(2,24); (*(M2[126]))[314] = M1(2,25); (*(M2[126]))[317] = M1(2,26); (*(M2[126]))[327] = M1(2,27); (*(M2[127]))[146] = M1(3,3); (*(M2[127]))[149] = M1(3,4); (*(M2[127]))[150] = M1(3,5); (*(M2[127]))[151] = M1(3,6); (*(M2[127]))[154] = M1(3,7); (*(M2[127]))[155] = M1(3,8); (*(M2[127]))[158] = M1(3,9); (*(M2[127]))[168] = M1(3,10); (*(M2[127]))[169] = M1(3,11); (*(M2[127]))[170] = M1(3,12); (*(M2[127]))[173] = M1(3,13); (*(M2[127]))[174] = M1(3,14); (*(M2[127]))[177] = M1(3,15); (*(M2[127]))[186] = M1(3,16); (*(M2[127]))[187] = M1(3,17); (*(M2[127]))[190] = M1(3,18); (*(M2[127]))[198] = M1(3,19); (*(M2[127]))[313] = M1(3,24); (*(M2[127]))[314] = M1(3,25); (*(M2[127]))[317] = M1(3,26); (*(M2[127]))[327] = M1(3,27); (*(M2[128]))[117] = M1(0,0); (*(M2[128]))[123] = M1(0,4); (*(M2[128]))[124] = M1(0,5); (*(M2[128]))[125] = M1(0,6); (*(M2[128]))[128] = M1(0,7); (*(M2[128]))[129] = M1(0,8); (*(M2[128]))[132] = M1(0,9); (*(M2[128]))[149] = M1(0,10); (*(M2[128]))[150] = M1(0,11); (*(M2[128]))[151] = M1(0,12); (*(M2[128]))[154] = M1(0,13); (*(M2[128]))[155] = M1(0,14); (*(M2[128]))[158] = M1(0,15); (*(M2[128]))[173] = M1(0,16); (*(M2[128]))[174] = M1(0,17); (*(M2[128]))[177] = M1(0,18); (*(M2[128]))[190] = M1(0,19); (*(M2[128]))[298] = M1(0,24); (*(M2[128]))[299] = M1(0,25); (*(M2[128]))[302] = M1(0,26); (*(M2[128]))[317] = M1(0,27); (*(M2[129]))[118] = M1(1,1); (*(M2[129]))[123] = M1(1,4); (*(M2[129]))[124] = M1(1,5); (*(M2[129]))[125] = M1(1,6); (*(M2[129]))[128] = M1(1,7); (*(M2[129]))[129] = M1(1,8); (*(M2[129]))[132] = M1(1,9); (*(M2[129]))[149] = M1(1,10); (*(M2[129]))[150] = M1(1,11); (*(M2[129]))[151] = M1(1,12); (*(M2[129]))[154] = M1(1,13); (*(M2[129]))[155] = M1(1,14); (*(M2[129]))[158] = M1(1,15); (*(M2[129]))[173] = M1(1,16); (*(M2[129]))[174] = M1(1,17); (*(M2[129]))[177] = M1(1,18); (*(M2[129]))[190] = M1(1,19); (*(M2[129]))[298] = M1(1,24); (*(M2[129]))[299] = M1(1,25); (*(M2[129]))[302] = M1(1,26); (*(M2[129]))[317] = M1(1,27); (*(M2[130]))[119] = M1(2,2); (*(M2[130]))[123] = M1(2,4); (*(M2[130]))[124] = M1(2,5); (*(M2[130]))[125] = M1(2,6); (*(M2[130]))[128] = M1(2,7); (*(M2[130]))[129] = M1(2,8); (*(M2[130]))[132] = M1(2,9); (*(M2[130]))[149] = M1(2,10); (*(M2[130]))[150] = M1(2,11); (*(M2[130]))[151] = M1(2,12); (*(M2[130]))[154] = M1(2,13); (*(M2[130]))[155] = M1(2,14); (*(M2[130]))[158] = M1(2,15); (*(M2[130]))[173] = M1(2,16); (*(M2[130]))[174] = M1(2,17); (*(M2[130]))[177] = M1(2,18); (*(M2[130]))[190] = M1(2,19); (*(M2[130]))[298] = M1(2,24); (*(M2[130]))[299] = M1(2,25); (*(M2[130]))[302] = M1(2,26); (*(M2[130]))[317] = M1(2,27); (*(M2[131]))[120] = M1(3,3); (*(M2[131]))[123] = M1(3,4); (*(M2[131]))[124] = M1(3,5); (*(M2[131]))[125] = M1(3,6); (*(M2[131]))[128] = M1(3,7); (*(M2[131]))[129] = M1(3,8); (*(M2[131]))[132] = M1(3,9); (*(M2[131]))[149] = M1(3,10); (*(M2[131]))[150] = M1(3,11); (*(M2[131]))[151] = M1(3,12); (*(M2[131]))[154] = M1(3,13); (*(M2[131]))[155] = M1(3,14); (*(M2[131]))[158] = M1(3,15); (*(M2[131]))[173] = M1(3,16); (*(M2[131]))[174] = M1(3,17); (*(M2[131]))[177] = M1(3,18); (*(M2[131]))[190] = M1(3,19); (*(M2[131]))[298] = M1(3,24); (*(M2[131]))[299] = M1(3,25); (*(M2[131]))[302] = M1(3,26); (*(M2[131]))[317] = M1(3,27); (*(M2[132]))[137] = M1(0,0); (*(M2[132]))[144] = M1(0,4); (*(M2[132]))[145] = M1(0,5); (*(M2[132]))[146] = M1(0,6); (*(M2[132]))[150] = M1(0,7); (*(M2[132]))[151] = M1(0,8); (*(M2[132]))[155] = M1(0,9); (*(M2[132]))[163] = M1(0,10); (*(M2[132]))[164] = M1(0,11); (*(M2[132]))[165] = M1(0,12); (*(M2[132]))[169] = M1(0,13); (*(M2[132]))[170] = M1(0,14); (*(M2[132]))[174] = M1(0,15); (*(M2[132]))[182] = M1(0,16); (*(M2[132]))[183] = M1(0,17); (*(M2[132]))[187] = M1(0,18); (*(M2[132]))[195] = M1(0,19); (*(M2[132]))[309] = M1(0,24); (*(M2[132]))[310] = M1(0,25); (*(M2[132]))[314] = M1(0,26); (*(M2[132]))[324] = M1(0,27); (*(M2[133]))[138] = M1(1,1); (*(M2[133]))[144] = M1(1,4); (*(M2[133]))[145] = M1(1,5); (*(M2[133]))[146] = M1(1,6); (*(M2[133]))[150] = M1(1,7); (*(M2[133]))[151] = M1(1,8); (*(M2[133]))[155] = M1(1,9); (*(M2[133]))[163] = M1(1,10); (*(M2[133]))[164] = M1(1,11); (*(M2[133]))[165] = M1(1,12); (*(M2[133]))[169] = M1(1,13); (*(M2[133]))[170] = M1(1,14); (*(M2[133]))[174] = M1(1,15); (*(M2[133]))[182] = M1(1,16); (*(M2[133]))[183] = M1(1,17); (*(M2[133]))[187] = M1(1,18); (*(M2[133]))[195] = M1(1,19); (*(M2[133]))[309] = M1(1,24); (*(M2[133]))[310] = M1(1,25); (*(M2[133]))[314] = M1(1,26); (*(M2[133]))[324] = M1(1,27); (*(M2[134]))[139] = M1(2,2); (*(M2[134]))[144] = M1(2,4); (*(M2[134]))[145] = M1(2,5); (*(M2[134]))[146] = M1(2,6); (*(M2[134]))[150] = M1(2,7); (*(M2[134]))[151] = M1(2,8); (*(M2[134]))[155] = M1(2,9); (*(M2[134]))[163] = M1(2,10); (*(M2[134]))[164] = M1(2,11); (*(M2[134]))[165] = M1(2,12); (*(M2[134]))[169] = M1(2,13); (*(M2[134]))[170] = M1(2,14); (*(M2[134]))[174] = M1(2,15); (*(M2[134]))[182] = M1(2,16); (*(M2[134]))[183] = M1(2,17); (*(M2[134]))[187] = M1(2,18); (*(M2[134]))[195] = M1(2,19); (*(M2[134]))[309] = M1(2,24); (*(M2[134]))[310] = M1(2,25); (*(M2[134]))[314] = M1(2,26); (*(M2[134]))[324] = M1(2,27); (*(M2[135]))[140] = M1(3,3); (*(M2[135]))[144] = M1(3,4); (*(M2[135]))[145] = M1(3,5); (*(M2[135]))[146] = M1(3,6); (*(M2[135]))[150] = M1(3,7); (*(M2[135]))[151] = M1(3,8); (*(M2[135]))[155] = M1(3,9); (*(M2[135]))[163] = M1(3,10); (*(M2[135]))[164] = M1(3,11); (*(M2[135]))[165] = M1(3,12); (*(M2[135]))[169] = M1(3,13); (*(M2[135]))[170] = M1(3,14); (*(M2[135]))[174] = M1(3,15); (*(M2[135]))[182] = M1(3,16); (*(M2[135]))[183] = M1(3,17); (*(M2[135]))[187] = M1(3,18); (*(M2[135]))[195] = M1(3,19); (*(M2[135]))[309] = M1(3,24); (*(M2[135]))[310] = M1(3,25); (*(M2[135]))[314] = M1(3,26); (*(M2[135]))[324] = M1(3,27); (*(M2[136]))[234] = M1(4,20); (*(M2[136]))[236] = M1(4,21); (*(M2[136]))[245] = M1(4,22); (*(M2[136]))[270] = M1(4,23); (*(M2[136]))[359] = M1(4,28); (*(M2[137]))[111] = M1(0,0); (*(M2[137]))[118] = M1(0,4); (*(M2[137]))[119] = M1(0,5); (*(M2[137]))[120] = M1(0,6); (*(M2[137]))[124] = M1(0,7); (*(M2[137]))[125] = M1(0,8); (*(M2[137]))[129] = M1(0,9); (*(M2[137]))[144] = M1(0,10); (*(M2[137]))[145] = M1(0,11); (*(M2[137]))[146] = M1(0,12); (*(M2[137]))[150] = M1(0,13); (*(M2[137]))[151] = M1(0,14); (*(M2[137]))[155] = M1(0,15); (*(M2[137]))[169] = M1(0,16); (*(M2[137]))[170] = M1(0,17); (*(M2[137]))[174] = M1(0,18); (*(M2[137]))[187] = M1(0,19); (*(M2[137]))[294] = M1(0,24); (*(M2[137]))[295] = M1(0,25); (*(M2[137]))[299] = M1(0,26); (*(M2[137]))[314] = M1(0,27); (*(M2[138]))[112] = M1(1,1); (*(M2[138]))[118] = M1(1,4); (*(M2[138]))[119] = M1(1,5); (*(M2[138]))[120] = M1(1,6); (*(M2[138]))[124] = M1(1,7); (*(M2[138]))[125] = M1(1,8); (*(M2[138]))[129] = M1(1,9); (*(M2[138]))[144] = M1(1,10); (*(M2[138]))[145] = M1(1,11); (*(M2[138]))[146] = M1(1,12); (*(M2[138]))[150] = M1(1,13); (*(M2[138]))[151] = M1(1,14); (*(M2[138]))[155] = M1(1,15); (*(M2[138]))[169] = M1(1,16); (*(M2[138]))[170] = M1(1,17); (*(M2[138]))[174] = M1(1,18); (*(M2[138]))[187] = M1(1,19); (*(M2[138]))[294] = M1(1,24); (*(M2[138]))[295] = M1(1,25); (*(M2[138]))[299] = M1(1,26); (*(M2[138]))[314] = M1(1,27); (*(M2[139]))[113] = M1(2,2); (*(M2[139]))[118] = M1(2,4); (*(M2[139]))[119] = M1(2,5); (*(M2[139]))[120] = M1(2,6); (*(M2[139]))[124] = M1(2,7); (*(M2[139]))[125] = M1(2,8); (*(M2[139]))[129] = M1(2,9); (*(M2[139]))[144] = M1(2,10); (*(M2[139]))[145] = M1(2,11); (*(M2[139]))[146] = M1(2,12); (*(M2[139]))[150] = M1(2,13); (*(M2[139]))[151] = M1(2,14); (*(M2[139]))[155] = M1(2,15); (*(M2[139]))[169] = M1(2,16); (*(M2[139]))[170] = M1(2,17); (*(M2[139]))[174] = M1(2,18); (*(M2[139]))[187] = M1(2,19); (*(M2[139]))[294] = M1(2,24); (*(M2[139]))[295] = M1(2,25); (*(M2[139]))[299] = M1(2,26); (*(M2[139]))[314] = M1(2,27); (*(M2[140]))[114] = M1(3,3); (*(M2[140]))[118] = M1(3,4); (*(M2[140]))[119] = M1(3,5); (*(M2[140]))[120] = M1(3,6); (*(M2[140]))[124] = M1(3,7); (*(M2[140]))[125] = M1(3,8); (*(M2[140]))[129] = M1(3,9); (*(M2[140]))[144] = M1(3,10); (*(M2[140]))[145] = M1(3,11); (*(M2[140]))[146] = M1(3,12); (*(M2[140]))[150] = M1(3,13); (*(M2[140]))[151] = M1(3,14); (*(M2[140]))[155] = M1(3,15); (*(M2[140]))[169] = M1(3,16); (*(M2[140]))[170] = M1(3,17); (*(M2[140]))[174] = M1(3,18); (*(M2[140]))[187] = M1(3,19); (*(M2[140]))[294] = M1(3,24); (*(M2[140]))[295] = M1(3,25); (*(M2[140]))[299] = M1(3,26); (*(M2[140]))[314] = M1(3,27); (*(M2[141]))[213] = M1(4,20); (*(M2[141]))[215] = M1(4,21); (*(M2[141]))[224] = M1(4,22); (*(M2[141]))[260] = M1(4,23); (*(M2[141]))[349] = M1(4,28); (*(M2[142]))[105] = M1(0,0); (*(M2[142]))[112] = M1(0,4); (*(M2[142]))[113] = M1(0,5); (*(M2[142]))[114] = M1(0,6); (*(M2[142]))[119] = M1(0,7); (*(M2[142]))[120] = M1(0,8); (*(M2[142]))[125] = M1(0,9); (*(M2[142]))[138] = M1(0,10); (*(M2[142]))[139] = M1(0,11); (*(M2[142]))[140] = M1(0,12); (*(M2[142]))[145] = M1(0,13); (*(M2[142]))[146] = M1(0,14); (*(M2[142]))[151] = M1(0,15); (*(M2[142]))[164] = M1(0,16); (*(M2[142]))[165] = M1(0,17); (*(M2[142]))[170] = M1(0,18); (*(M2[142]))[183] = M1(0,19); (*(M2[142]))[289] = M1(0,24); (*(M2[142]))[290] = M1(0,25); (*(M2[142]))[295] = M1(0,26); (*(M2[142]))[310] = M1(0,27); (*(M2[143]))[106] = M1(1,1); (*(M2[143]))[112] = M1(1,4); (*(M2[143]))[113] = M1(1,5); (*(M2[143]))[114] = M1(1,6); (*(M2[143]))[119] = M1(1,7); (*(M2[143]))[120] = M1(1,8); (*(M2[143]))[125] = M1(1,9); (*(M2[143]))[138] = M1(1,10); (*(M2[143]))[139] = M1(1,11); (*(M2[143]))[140] = M1(1,12); (*(M2[143]))[145] = M1(1,13); (*(M2[143]))[146] = M1(1,14); (*(M2[143]))[151] = M1(1,15); (*(M2[143]))[164] = M1(1,16); (*(M2[143]))[165] = M1(1,17); (*(M2[143]))[170] = M1(1,18); (*(M2[143]))[183] = M1(1,19); (*(M2[143]))[289] = M1(1,24); (*(M2[143]))[290] = M1(1,25); (*(M2[143]))[295] = M1(1,26); (*(M2[143]))[310] = M1(1,27); (*(M2[144]))[107] = M1(2,2); (*(M2[144]))[112] = M1(2,4); (*(M2[144]))[113] = M1(2,5); (*(M2[144]))[114] = M1(2,6); (*(M2[144]))[119] = M1(2,7); (*(M2[144]))[120] = M1(2,8); (*(M2[144]))[125] = M1(2,9); (*(M2[144]))[138] = M1(2,10); (*(M2[144]))[139] = M1(2,11); (*(M2[144]))[140] = M1(2,12); (*(M2[144]))[145] = M1(2,13); (*(M2[144]))[146] = M1(2,14); (*(M2[144]))[151] = M1(2,15); (*(M2[144]))[164] = M1(2,16); (*(M2[144]))[165] = M1(2,17); (*(M2[144]))[170] = M1(2,18); (*(M2[144]))[183] = M1(2,19); (*(M2[144]))[289] = M1(2,24); (*(M2[144]))[290] = M1(2,25); (*(M2[144]))[295] = M1(2,26); (*(M2[144]))[310] = M1(2,27); (*(M2[145]))[207] = M1(4,20); (*(M2[145]))[209] = M1(4,21); (*(M2[145]))[220] = M1(4,22); (*(M2[145]))[256] = M1(4,23); (*(M2[145]))[345] = M1(4,28); (*(M2[146]))[148] = M1(1,1); (*(M2[146]))[152] = M1(1,4); (*(M2[146]))[153] = M1(1,5); (*(M2[146]))[154] = M1(1,6); (*(M2[146]))[156] = M1(1,7); (*(M2[146]))[157] = M1(1,8); (*(M2[146]))[159] = M1(1,9); (*(M2[146]))[171] = M1(1,10); (*(M2[146]))[172] = M1(1,11); (*(M2[146]))[173] = M1(1,12); (*(M2[146]))[175] = M1(1,13); (*(M2[146]))[176] = M1(1,14); (*(M2[146]))[178] = M1(1,15); (*(M2[146]))[188] = M1(1,16); (*(M2[146]))[189] = M1(1,17); (*(M2[146]))[191] = M1(1,18); (*(M2[146]))[199] = M1(1,19); (*(M2[146]))[315] = M1(1,24); (*(M2[146]))[316] = M1(1,25); (*(M2[146]))[318] = M1(1,26); (*(M2[146]))[328] = M1(1,27); (*(M2[147]))[149] = M1(2,2); (*(M2[147]))[152] = M1(2,4); (*(M2[147]))[153] = M1(2,5); (*(M2[147]))[154] = M1(2,6); (*(M2[147]))[156] = M1(2,7); (*(M2[147]))[157] = M1(2,8); (*(M2[147]))[159] = M1(2,9); (*(M2[147]))[171] = M1(2,10); (*(M2[147]))[172] = M1(2,11); (*(M2[147]))[173] = M1(2,12); (*(M2[147]))[175] = M1(2,13); (*(M2[147]))[176] = M1(2,14); (*(M2[147]))[178] = M1(2,15); (*(M2[147]))[188] = M1(2,16); (*(M2[147]))[189] = M1(2,17); (*(M2[147]))[191] = M1(2,18); (*(M2[147]))[199] = M1(2,19); (*(M2[147]))[315] = M1(2,24); (*(M2[147]))[316] = M1(2,25); (*(M2[147]))[318] = M1(2,26); (*(M2[147]))[328] = M1(2,27); (*(M2[148]))[150] = M1(3,3); (*(M2[148]))[152] = M1(3,4); (*(M2[148]))[153] = M1(3,5); (*(M2[148]))[154] = M1(3,6); (*(M2[148]))[156] = M1(3,7); (*(M2[148]))[157] = M1(3,8); (*(M2[148]))[159] = M1(3,9); (*(M2[148]))[171] = M1(3,10); (*(M2[148]))[172] = M1(3,11); (*(M2[148]))[173] = M1(3,12); (*(M2[148]))[175] = M1(3,13); (*(M2[148]))[176] = M1(3,14); (*(M2[148]))[178] = M1(3,15); (*(M2[148]))[188] = M1(3,16); (*(M2[148]))[189] = M1(3,17); (*(M2[148]))[191] = M1(3,18); (*(M2[148]))[199] = M1(3,19); (*(M2[148]))[315] = M1(3,24); (*(M2[148]))[316] = M1(3,25); (*(M2[148]))[318] = M1(3,26); (*(M2[148]))[328] = M1(3,27); (*(M2[149]))[121] = M1(0,0); (*(M2[149]))[126] = M1(0,4); (*(M2[149]))[127] = M1(0,5); (*(M2[149]))[128] = M1(0,6); (*(M2[149]))[130] = M1(0,7); (*(M2[149]))[131] = M1(0,8); (*(M2[149]))[133] = M1(0,9); (*(M2[149]))[152] = M1(0,10); (*(M2[149]))[153] = M1(0,11); (*(M2[149]))[154] = M1(0,12); (*(M2[149]))[156] = M1(0,13); (*(M2[149]))[157] = M1(0,14); (*(M2[149]))[159] = M1(0,15); (*(M2[149]))[175] = M1(0,16); (*(M2[149]))[176] = M1(0,17); (*(M2[149]))[178] = M1(0,18); (*(M2[149]))[191] = M1(0,19); (*(M2[149]))[300] = M1(0,24); (*(M2[149]))[301] = M1(0,25); (*(M2[149]))[303] = M1(0,26); (*(M2[149]))[318] = M1(0,27); (*(M2[150]))[122] = M1(1,1); (*(M2[150]))[126] = M1(1,4); (*(M2[150]))[127] = M1(1,5); (*(M2[150]))[128] = M1(1,6); (*(M2[150]))[130] = M1(1,7); (*(M2[150]))[131] = M1(1,8); (*(M2[150]))[133] = M1(1,9); (*(M2[150]))[152] = M1(1,10); (*(M2[150]))[153] = M1(1,11); (*(M2[150]))[154] = M1(1,12); (*(M2[150]))[156] = M1(1,13); (*(M2[150]))[157] = M1(1,14); (*(M2[150]))[159] = M1(1,15); (*(M2[150]))[175] = M1(1,16); (*(M2[150]))[176] = M1(1,17); (*(M2[150]))[178] = M1(1,18); (*(M2[150]))[191] = M1(1,19); (*(M2[150]))[300] = M1(1,24); (*(M2[150]))[301] = M1(1,25); (*(M2[150]))[303] = M1(1,26); (*(M2[150]))[318] = M1(1,27); (*(M2[151]))[123] = M1(2,2); (*(M2[151]))[126] = M1(2,4); (*(M2[151]))[127] = M1(2,5); (*(M2[151]))[128] = M1(2,6); (*(M2[151]))[130] = M1(2,7); (*(M2[151]))[131] = M1(2,8); (*(M2[151]))[133] = M1(2,9); (*(M2[151]))[152] = M1(2,10); (*(M2[151]))[153] = M1(2,11); (*(M2[151]))[154] = M1(2,12); (*(M2[151]))[156] = M1(2,13); (*(M2[151]))[157] = M1(2,14); (*(M2[151]))[159] = M1(2,15); (*(M2[151]))[175] = M1(2,16); (*(M2[151]))[176] = M1(2,17); (*(M2[151]))[178] = M1(2,18); (*(M2[151]))[191] = M1(2,19); (*(M2[151]))[300] = M1(2,24); (*(M2[151]))[301] = M1(2,25); (*(M2[151]))[303] = M1(2,26); (*(M2[151]))[318] = M1(2,27); (*(M2[152]))[124] = M1(3,3); (*(M2[152]))[126] = M1(3,4); (*(M2[152]))[127] = M1(3,5); (*(M2[152]))[128] = M1(3,6); (*(M2[152]))[130] = M1(3,7); (*(M2[152]))[131] = M1(3,8); (*(M2[152]))[133] = M1(3,9); (*(M2[152]))[152] = M1(3,10); (*(M2[152]))[153] = M1(3,11); (*(M2[152]))[154] = M1(3,12); (*(M2[152]))[156] = M1(3,13); (*(M2[152]))[157] = M1(3,14); (*(M2[152]))[159] = M1(3,15); (*(M2[152]))[175] = M1(3,16); (*(M2[152]))[176] = M1(3,17); (*(M2[152]))[178] = M1(3,18); (*(M2[152]))[191] = M1(3,19); (*(M2[152]))[300] = M1(3,24); (*(M2[152]))[301] = M1(3,25); (*(M2[152]))[303] = M1(3,26); (*(M2[152]))[318] = M1(3,27); (*(M2[153]))[161] = M1(0,0); (*(M2[153]))[167] = M1(0,4); (*(M2[153]))[168] = M1(0,5); (*(M2[153]))[169] = M1(0,6); (*(M2[153]))[172] = M1(0,7); (*(M2[153]))[173] = M1(0,8); (*(M2[153]))[176] = M1(0,9); (*(M2[153]))[180] = M1(0,10); (*(M2[153]))[181] = M1(0,11); (*(M2[153]))[182] = M1(0,12); (*(M2[153]))[185] = M1(0,13); (*(M2[153]))[186] = M1(0,14); (*(M2[153]))[189] = M1(0,15); (*(M2[153]))[193] = M1(0,16); (*(M2[153]))[194] = M1(0,17); (*(M2[153]))[197] = M1(0,18); (*(M2[153]))[201] = M1(0,19); (*(M2[153]))[322] = M1(0,24); (*(M2[153]))[323] = M1(0,25); (*(M2[153]))[326] = M1(0,26); (*(M2[153]))[332] = M1(0,27); (*(M2[154]))[162] = M1(1,1); (*(M2[154]))[167] = M1(1,4); (*(M2[154]))[168] = M1(1,5); (*(M2[154]))[169] = M1(1,6); (*(M2[154]))[172] = M1(1,7); (*(M2[154]))[173] = M1(1,8); (*(M2[154]))[176] = M1(1,9); (*(M2[154]))[180] = M1(1,10); (*(M2[154]))[181] = M1(1,11); (*(M2[154]))[182] = M1(1,12); (*(M2[154]))[185] = M1(1,13); (*(M2[154]))[186] = M1(1,14); (*(M2[154]))[189] = M1(1,15); (*(M2[154]))[193] = M1(1,16); (*(M2[154]))[194] = M1(1,17); (*(M2[154]))[197] = M1(1,18); (*(M2[154]))[201] = M1(1,19); (*(M2[154]))[322] = M1(1,24); (*(M2[154]))[323] = M1(1,25); (*(M2[154]))[326] = M1(1,26); (*(M2[154]))[332] = M1(1,27); (*(M2[155]))[163] = M1(2,2); (*(M2[155]))[167] = M1(2,4); (*(M2[155]))[168] = M1(2,5); (*(M2[155]))[169] = M1(2,6); (*(M2[155]))[172] = M1(2,7); (*(M2[155]))[173] = M1(2,8); (*(M2[155]))[176] = M1(2,9); (*(M2[155]))[180] = M1(2,10); (*(M2[155]))[181] = M1(2,11); (*(M2[155]))[182] = M1(2,12); (*(M2[155]))[185] = M1(2,13); (*(M2[155]))[186] = M1(2,14); (*(M2[155]))[189] = M1(2,15); (*(M2[155]))[193] = M1(2,16); (*(M2[155]))[194] = M1(2,17); (*(M2[155]))[197] = M1(2,18); (*(M2[155]))[201] = M1(2,19); (*(M2[155]))[322] = M1(2,24); (*(M2[155]))[323] = M1(2,25); (*(M2[155]))[326] = M1(2,26); (*(M2[155]))[332] = M1(2,27); (*(M2[156]))[164] = M1(3,3); (*(M2[156]))[167] = M1(3,4); (*(M2[156]))[168] = M1(3,5); (*(M2[156]))[169] = M1(3,6); (*(M2[156]))[172] = M1(3,7); (*(M2[156]))[173] = M1(3,8); (*(M2[156]))[176] = M1(3,9); (*(M2[156]))[180] = M1(3,10); (*(M2[156]))[181] = M1(3,11); (*(M2[156]))[182] = M1(3,12); (*(M2[156]))[185] = M1(3,13); (*(M2[156]))[186] = M1(3,14); (*(M2[156]))[189] = M1(3,15); (*(M2[156]))[193] = M1(3,16); (*(M2[156]))[194] = M1(3,17); (*(M2[156]))[197] = M1(3,18); (*(M2[156]))[201] = M1(3,19); (*(M2[156]))[322] = M1(3,24); (*(M2[156]))[323] = M1(3,25); (*(M2[156]))[326] = M1(3,26); (*(M2[156]))[332] = M1(3,27); (*(M2[157]))[253] = M1(4,20); (*(M2[157]))[255] = M1(4,21); (*(M2[157]))[262] = M1(4,22); (*(M2[157]))[278] = M1(4,23); (*(M2[157]))[367] = M1(4,28); (*(M2[158]))[142] = M1(0,0); (*(M2[158]))[148] = M1(0,4); (*(M2[158]))[149] = M1(0,5); (*(M2[158]))[150] = M1(0,6); (*(M2[158]))[153] = M1(0,7); (*(M2[158]))[154] = M1(0,8); (*(M2[158]))[157] = M1(0,9); (*(M2[158]))[167] = M1(0,10); (*(M2[158]))[168] = M1(0,11); (*(M2[158]))[169] = M1(0,12); (*(M2[158]))[172] = M1(0,13); (*(M2[158]))[173] = M1(0,14); (*(M2[158]))[176] = M1(0,15); (*(M2[158]))[185] = M1(0,16); (*(M2[158]))[186] = M1(0,17); (*(M2[158]))[189] = M1(0,18); (*(M2[158]))[197] = M1(0,19); (*(M2[158]))[312] = M1(0,24); (*(M2[158]))[313] = M1(0,25); (*(M2[158]))[316] = M1(0,26); (*(M2[158]))[326] = M1(0,27); (*(M2[159]))[143] = M1(1,1); (*(M2[159]))[148] = M1(1,4); (*(M2[159]))[149] = M1(1,5); (*(M2[159]))[150] = M1(1,6); (*(M2[159]))[153] = M1(1,7); (*(M2[159]))[154] = M1(1,8); (*(M2[159]))[157] = M1(1,9); (*(M2[159]))[167] = M1(1,10); (*(M2[159]))[168] = M1(1,11); (*(M2[159]))[169] = M1(1,12); (*(M2[159]))[172] = M1(1,13); (*(M2[159]))[173] = M1(1,14); (*(M2[159]))[176] = M1(1,15); (*(M2[159]))[185] = M1(1,16); (*(M2[159]))[186] = M1(1,17); (*(M2[159]))[189] = M1(1,18); (*(M2[159]))[197] = M1(1,19); (*(M2[159]))[312] = M1(1,24); (*(M2[159]))[313] = M1(1,25); (*(M2[159]))[316] = M1(1,26); (*(M2[159]))[326] = M1(1,27); (*(M2[160]))[144] = M1(2,2); (*(M2[160]))[148] = M1(2,4); (*(M2[160]))[149] = M1(2,5); (*(M2[160]))[150] = M1(2,6); (*(M2[160]))[153] = M1(2,7); (*(M2[160]))[154] = M1(2,8); (*(M2[160]))[157] = M1(2,9); (*(M2[160]))[167] = M1(2,10); (*(M2[160]))[168] = M1(2,11); (*(M2[160]))[169] = M1(2,12); (*(M2[160]))[172] = M1(2,13); (*(M2[160]))[173] = M1(2,14); (*(M2[160]))[176] = M1(2,15); (*(M2[160]))[185] = M1(2,16); (*(M2[160]))[186] = M1(2,17); (*(M2[160]))[189] = M1(2,18); (*(M2[160]))[197] = M1(2,19); (*(M2[160]))[312] = M1(2,24); (*(M2[160]))[313] = M1(2,25); (*(M2[160]))[316] = M1(2,26); (*(M2[160]))[326] = M1(2,27); (*(M2[161]))[145] = M1(3,3); (*(M2[161]))[148] = M1(3,4); (*(M2[161]))[149] = M1(3,5); (*(M2[161]))[150] = M1(3,6); (*(M2[161]))[153] = M1(3,7); (*(M2[161]))[154] = M1(3,8); (*(M2[161]))[157] = M1(3,9); (*(M2[161]))[167] = M1(3,10); (*(M2[161]))[168] = M1(3,11); (*(M2[161]))[169] = M1(3,12); (*(M2[161]))[172] = M1(3,13); (*(M2[161]))[173] = M1(3,14); (*(M2[161]))[176] = M1(3,15); (*(M2[161]))[185] = M1(3,16); (*(M2[161]))[186] = M1(3,17); (*(M2[161]))[189] = M1(3,18); (*(M2[161]))[197] = M1(3,19); (*(M2[161]))[312] = M1(3,24); (*(M2[161]))[313] = M1(3,25); (*(M2[161]))[316] = M1(3,26); (*(M2[161]))[326] = M1(3,27); (*(M2[162]))[238] = M1(4,20); (*(M2[162]))[240] = M1(4,21); (*(M2[162]))[247] = M1(4,22); (*(M2[162]))[272] = M1(4,23); (*(M2[162]))[361] = M1(4,28); (*(M2[163]))[116] = M1(0,0); (*(M2[163]))[122] = M1(0,4); (*(M2[163]))[123] = M1(0,5); (*(M2[163]))[124] = M1(0,6); (*(M2[163]))[127] = M1(0,7); (*(M2[163]))[128] = M1(0,8); (*(M2[163]))[131] = M1(0,9); (*(M2[163]))[148] = M1(0,10); (*(M2[163]))[149] = M1(0,11); (*(M2[163]))[150] = M1(0,12); (*(M2[163]))[153] = M1(0,13); (*(M2[163]))[154] = M1(0,14); (*(M2[163]))[157] = M1(0,15); (*(M2[163]))[172] = M1(0,16); (*(M2[163]))[173] = M1(0,17); (*(M2[163]))[176] = M1(0,18); (*(M2[163]))[189] = M1(0,19); (*(M2[163]))[297] = M1(0,24); (*(M2[163]))[298] = M1(0,25); (*(M2[163]))[301] = M1(0,26); (*(M2[163]))[316] = M1(0,27); (*(M2[164]))[117] = M1(1,1); (*(M2[164]))[122] = M1(1,4); (*(M2[164]))[123] = M1(1,5); (*(M2[164]))[124] = M1(1,6); (*(M2[164]))[127] = M1(1,7); (*(M2[164]))[128] = M1(1,8); (*(M2[164]))[131] = M1(1,9); (*(M2[164]))[148] = M1(1,10); (*(M2[164]))[149] = M1(1,11); (*(M2[164]))[150] = M1(1,12); (*(M2[164]))[153] = M1(1,13); (*(M2[164]))[154] = M1(1,14); (*(M2[164]))[157] = M1(1,15); (*(M2[164]))[172] = M1(1,16); (*(M2[164]))[173] = M1(1,17); (*(M2[164]))[176] = M1(1,18); (*(M2[164]))[189] = M1(1,19); (*(M2[164]))[297] = M1(1,24); (*(M2[164]))[298] = M1(1,25); (*(M2[164]))[301] = M1(1,26); (*(M2[164]))[316] = M1(1,27); (*(M2[165]))[118] = M1(2,2); (*(M2[165]))[122] = M1(2,4); (*(M2[165]))[123] = M1(2,5); (*(M2[165]))[124] = M1(2,6); (*(M2[165]))[127] = M1(2,7); (*(M2[165]))[128] = M1(2,8); (*(M2[165]))[131] = M1(2,9); (*(M2[165]))[148] = M1(2,10); (*(M2[165]))[149] = M1(2,11); (*(M2[165]))[150] = M1(2,12); (*(M2[165]))[153] = M1(2,13); (*(M2[165]))[154] = M1(2,14); (*(M2[165]))[157] = M1(2,15); (*(M2[165]))[172] = M1(2,16); (*(M2[165]))[173] = M1(2,17); (*(M2[165]))[176] = M1(2,18); (*(M2[165]))[189] = M1(2,19); (*(M2[165]))[297] = M1(2,24); (*(M2[165]))[298] = M1(2,25); (*(M2[165]))[301] = M1(2,26); (*(M2[165]))[316] = M1(2,27); (*(M2[166]))[119] = M1(3,3); (*(M2[166]))[122] = M1(3,4); (*(M2[166]))[123] = M1(3,5); (*(M2[166]))[124] = M1(3,6); (*(M2[166]))[127] = M1(3,7); (*(M2[166]))[128] = M1(3,8); (*(M2[166]))[131] = M1(3,9); (*(M2[166]))[148] = M1(3,10); (*(M2[166]))[149] = M1(3,11); (*(M2[166]))[150] = M1(3,12); (*(M2[166]))[153] = M1(3,13); (*(M2[166]))[154] = M1(3,14); (*(M2[166]))[157] = M1(3,15); (*(M2[166]))[172] = M1(3,16); (*(M2[166]))[173] = M1(3,17); (*(M2[166]))[176] = M1(3,18); (*(M2[166]))[189] = M1(3,19); (*(M2[166]))[297] = M1(3,24); (*(M2[166]))[298] = M1(3,25); (*(M2[166]))[301] = M1(3,26); (*(M2[166]))[316] = M1(3,27); (*(M2[167]))[217] = M1(4,20); (*(M2[167]))[219] = M1(4,21); (*(M2[167]))[226] = M1(4,22); (*(M2[167]))[262] = M1(4,23); (*(M2[167]))[351] = M1(4,28); (*(M2[168]))[136] = M1(0,0); (*(M2[168]))[143] = M1(0,4); (*(M2[168]))[144] = M1(0,5); (*(M2[168]))[145] = M1(0,6); (*(M2[168]))[149] = M1(0,7); (*(M2[168]))[150] = M1(0,8); (*(M2[168]))[154] = M1(0,9); (*(M2[168]))[162] = M1(0,10); (*(M2[168]))[163] = M1(0,11); (*(M2[168]))[164] = M1(0,12); (*(M2[168]))[168] = M1(0,13); (*(M2[168]))[169] = M1(0,14); (*(M2[168]))[173] = M1(0,15); (*(M2[168]))[181] = M1(0,16); (*(M2[168]))[182] = M1(0,17); (*(M2[168]))[186] = M1(0,18); (*(M2[168]))[194] = M1(0,19); (*(M2[168]))[308] = M1(0,24); (*(M2[168]))[309] = M1(0,25); (*(M2[168]))[313] = M1(0,26); (*(M2[168]))[323] = M1(0,27); (*(M2[169]))[137] = M1(1,1); (*(M2[169]))[143] = M1(1,4); (*(M2[169]))[144] = M1(1,5); (*(M2[169]))[145] = M1(1,6); (*(M2[169]))[149] = M1(1,7); (*(M2[169]))[150] = M1(1,8); (*(M2[169]))[154] = M1(1,9); (*(M2[169]))[162] = M1(1,10); (*(M2[169]))[163] = M1(1,11); (*(M2[169]))[164] = M1(1,12); (*(M2[169]))[168] = M1(1,13); (*(M2[169]))[169] = M1(1,14); (*(M2[169]))[173] = M1(1,15); (*(M2[169]))[181] = M1(1,16); (*(M2[169]))[182] = M1(1,17); (*(M2[169]))[186] = M1(1,18); (*(M2[169]))[194] = M1(1,19); (*(M2[169]))[308] = M1(1,24); (*(M2[169]))[309] = M1(1,25); (*(M2[169]))[313] = M1(1,26); (*(M2[169]))[323] = M1(1,27); (*(M2[170]))[138] = M1(2,2); (*(M2[170]))[143] = M1(2,4); (*(M2[170]))[144] = M1(2,5); (*(M2[170]))[145] = M1(2,6); (*(M2[170]))[149] = M1(2,7); (*(M2[170]))[150] = M1(2,8); (*(M2[170]))[154] = M1(2,9); (*(M2[170]))[162] = M1(2,10); (*(M2[170]))[163] = M1(2,11); (*(M2[170]))[164] = M1(2,12); (*(M2[170]))[168] = M1(2,13); (*(M2[170]))[169] = M1(2,14); (*(M2[170]))[173] = M1(2,15); (*(M2[170]))[181] = M1(2,16); (*(M2[170]))[182] = M1(2,17); (*(M2[170]))[186] = M1(2,18); (*(M2[170]))[194] = M1(2,19); (*(M2[170]))[308] = M1(2,24); (*(M2[170]))[309] = M1(2,25); (*(M2[170]))[313] = M1(2,26); (*(M2[170]))[323] = M1(2,27); (*(M2[171]))[139] = M1(3,3); (*(M2[171]))[143] = M1(3,4); (*(M2[171]))[144] = M1(3,5); (*(M2[171]))[145] = M1(3,6); (*(M2[171]))[149] = M1(3,7); (*(M2[171]))[150] = M1(3,8); (*(M2[171]))[154] = M1(3,9); (*(M2[171]))[162] = M1(3,10); (*(M2[171]))[163] = M1(3,11); (*(M2[171]))[164] = M1(3,12); (*(M2[171]))[168] = M1(3,13); (*(M2[171]))[169] = M1(3,14); (*(M2[171]))[173] = M1(3,15); (*(M2[171]))[181] = M1(3,16); (*(M2[171]))[182] = M1(3,17); (*(M2[171]))[186] = M1(3,18); (*(M2[171]))[194] = M1(3,19); (*(M2[171]))[308] = M1(3,24); (*(M2[171]))[309] = M1(3,25); (*(M2[171]))[313] = M1(3,26); (*(M2[171]))[323] = M1(3,27); (*(M2[172]))[233] = M1(4,20); (*(M2[172]))[235] = M1(4,21); (*(M2[172]))[244] = M1(4,22); (*(M2[172]))[269] = M1(4,23); (*(M2[172]))[358] = M1(4,28); (*(M2[173]))[110] = M1(0,0); (*(M2[173]))[117] = M1(0,4); (*(M2[173]))[118] = M1(0,5); (*(M2[173]))[119] = M1(0,6); (*(M2[173]))[123] = M1(0,7); (*(M2[173]))[124] = M1(0,8); (*(M2[173]))[128] = M1(0,9); (*(M2[173]))[143] = M1(0,10); (*(M2[173]))[144] = M1(0,11); (*(M2[173]))[145] = M1(0,12); (*(M2[173]))[149] = M1(0,13); (*(M2[173]))[150] = M1(0,14); (*(M2[173]))[154] = M1(0,15); (*(M2[173]))[168] = M1(0,16); (*(M2[173]))[169] = M1(0,17); (*(M2[173]))[173] = M1(0,18); (*(M2[173]))[186] = M1(0,19); (*(M2[173]))[293] = M1(0,24); (*(M2[173]))[294] = M1(0,25); (*(M2[173]))[298] = M1(0,26); (*(M2[173]))[313] = M1(0,27); (*(M2[174]))[111] = M1(1,1); (*(M2[174]))[117] = M1(1,4); (*(M2[174]))[118] = M1(1,5); (*(M2[174]))[119] = M1(1,6); (*(M2[174]))[123] = M1(1,7); (*(M2[174]))[124] = M1(1,8); (*(M2[174]))[128] = M1(1,9); (*(M2[174]))[143] = M1(1,10); (*(M2[174]))[144] = M1(1,11); (*(M2[174]))[145] = M1(1,12); (*(M2[174]))[149] = M1(1,13); (*(M2[174]))[150] = M1(1,14); (*(M2[174]))[154] = M1(1,15); (*(M2[174]))[168] = M1(1,16); (*(M2[174]))[169] = M1(1,17); (*(M2[174]))[173] = M1(1,18); (*(M2[174]))[186] = M1(1,19); (*(M2[174]))[293] = M1(1,24); (*(M2[174]))[294] = M1(1,25); (*(M2[174]))[298] = M1(1,26); (*(M2[174]))[313] = M1(1,27); (*(M2[175]))[112] = M1(2,2); (*(M2[175]))[117] = M1(2,4); (*(M2[175]))[118] = M1(2,5); (*(M2[175]))[119] = M1(2,6); (*(M2[175]))[123] = M1(2,7); (*(M2[175]))[124] = M1(2,8); (*(M2[175]))[128] = M1(2,9); (*(M2[175]))[143] = M1(2,10); (*(M2[175]))[144] = M1(2,11); (*(M2[175]))[145] = M1(2,12); (*(M2[175]))[149] = M1(2,13); (*(M2[175]))[150] = M1(2,14); (*(M2[175]))[154] = M1(2,15); (*(M2[175]))[168] = M1(2,16); (*(M2[175]))[169] = M1(2,17); (*(M2[175]))[173] = M1(2,18); (*(M2[175]))[186] = M1(2,19); (*(M2[175]))[293] = M1(2,24); (*(M2[175]))[294] = M1(2,25); (*(M2[175]))[298] = M1(2,26); (*(M2[175]))[313] = M1(2,27); (*(M2[176]))[113] = M1(3,3); (*(M2[176]))[117] = M1(3,4); (*(M2[176]))[118] = M1(3,5); (*(M2[176]))[119] = M1(3,6); (*(M2[176]))[123] = M1(3,7); (*(M2[176]))[124] = M1(3,8); (*(M2[176]))[128] = M1(3,9); (*(M2[176]))[143] = M1(3,10); (*(M2[176]))[144] = M1(3,11); (*(M2[176]))[145] = M1(3,12); (*(M2[176]))[149] = M1(3,13); (*(M2[176]))[150] = M1(3,14); (*(M2[176]))[154] = M1(3,15); (*(M2[176]))[168] = M1(3,16); (*(M2[176]))[169] = M1(3,17); (*(M2[176]))[173] = M1(3,18); (*(M2[176]))[186] = M1(3,19); (*(M2[176]))[293] = M1(3,24); (*(M2[176]))[294] = M1(3,25); (*(M2[176]))[298] = M1(3,26); (*(M2[176]))[313] = M1(3,27); (*(M2[177]))[212] = M1(4,20); (*(M2[177]))[214] = M1(4,21); (*(M2[177]))[223] = M1(4,22); (*(M2[177]))[259] = M1(4,23); (*(M2[177]))[348] = M1(4,28); (*(M2[178]))[104] = M1(0,0); (*(M2[178]))[111] = M1(0,4); (*(M2[178]))[112] = M1(0,5); (*(M2[178]))[113] = M1(0,6); (*(M2[178]))[118] = M1(0,7); (*(M2[178]))[119] = M1(0,8); (*(M2[178]))[124] = M1(0,9); (*(M2[178]))[137] = M1(0,10); (*(M2[178]))[138] = M1(0,11); (*(M2[178]))[139] = M1(0,12); (*(M2[178]))[144] = M1(0,13); (*(M2[178]))[145] = M1(0,14); (*(M2[178]))[150] = M1(0,15); (*(M2[178]))[163] = M1(0,16); (*(M2[178]))[164] = M1(0,17); (*(M2[178]))[169] = M1(0,18); (*(M2[178]))[182] = M1(0,19); (*(M2[178]))[288] = M1(0,24); (*(M2[178]))[289] = M1(0,25); (*(M2[178]))[294] = M1(0,26); (*(M2[178]))[309] = M1(0,27); (*(M2[179]))[105] = M1(1,1); (*(M2[179]))[111] = M1(1,4); (*(M2[179]))[112] = M1(1,5); (*(M2[179]))[113] = M1(1,6); (*(M2[179]))[118] = M1(1,7); (*(M2[179]))[119] = M1(1,8); (*(M2[179]))[124] = M1(1,9); (*(M2[179]))[137] = M1(1,10); (*(M2[179]))[138] = M1(1,11); (*(M2[179]))[139] = M1(1,12); (*(M2[179]))[144] = M1(1,13); (*(M2[179]))[145] = M1(1,14); (*(M2[179]))[150] = M1(1,15); (*(M2[179]))[163] = M1(1,16); (*(M2[179]))[164] = M1(1,17); (*(M2[179]))[169] = M1(1,18); (*(M2[179]))[182] = M1(1,19); (*(M2[179]))[288] = M1(1,24); (*(M2[179]))[289] = M1(1,25); (*(M2[179]))[294] = M1(1,26); (*(M2[179]))[309] = M1(1,27); (*(M2[180]))[106] = M1(2,2); (*(M2[180]))[111] = M1(2,4); (*(M2[180]))[112] = M1(2,5); (*(M2[180]))[113] = M1(2,6); (*(M2[180]))[118] = M1(2,7); (*(M2[180]))[119] = M1(2,8); (*(M2[180]))[124] = M1(2,9); (*(M2[180]))[137] = M1(2,10); (*(M2[180]))[138] = M1(2,11); (*(M2[180]))[139] = M1(2,12); (*(M2[180]))[144] = M1(2,13); (*(M2[180]))[145] = M1(2,14); (*(M2[180]))[150] = M1(2,15); (*(M2[180]))[163] = M1(2,16); (*(M2[180]))[164] = M1(2,17); (*(M2[180]))[169] = M1(2,18); (*(M2[180]))[182] = M1(2,19); (*(M2[180]))[288] = M1(2,24); (*(M2[180]))[289] = M1(2,25); (*(M2[180]))[294] = M1(2,26); (*(M2[180]))[309] = M1(2,27); (*(M2[181]))[107] = M1(3,3); (*(M2[181]))[111] = M1(3,4); (*(M2[181]))[112] = M1(3,5); (*(M2[181]))[113] = M1(3,6); (*(M2[181]))[118] = M1(3,7); (*(M2[181]))[119] = M1(3,8); (*(M2[181]))[124] = M1(3,9); (*(M2[181]))[137] = M1(3,10); (*(M2[181]))[138] = M1(3,11); (*(M2[181]))[139] = M1(3,12); (*(M2[181]))[144] = M1(3,13); (*(M2[181]))[145] = M1(3,14); (*(M2[181]))[150] = M1(3,15); (*(M2[181]))[163] = M1(3,16); (*(M2[181]))[164] = M1(3,17); (*(M2[181]))[169] = M1(3,18); (*(M2[181]))[182] = M1(3,19); (*(M2[181]))[288] = M1(3,24); (*(M2[181]))[289] = M1(3,25); (*(M2[181]))[294] = M1(3,26); (*(M2[181]))[309] = M1(3,27); (*(M2[182]))[206] = M1(4,20); (*(M2[182]))[208] = M1(4,21); (*(M2[182]))[219] = M1(4,22); (*(M2[182]))[255] = M1(4,23); (*(M2[182]))[344] = M1(4,28); (*(M2[183]))[160] = M1(0,0); (*(M2[183]))[166] = M1(0,4); (*(M2[183]))[167] = M1(0,5); (*(M2[183]))[168] = M1(0,6); (*(M2[183]))[171] = M1(0,7); (*(M2[183]))[172] = M1(0,8); (*(M2[183]))[175] = M1(0,9); (*(M2[183]))[179] = M1(0,10); (*(M2[183]))[180] = M1(0,11); (*(M2[183]))[181] = M1(0,12); (*(M2[183]))[184] = M1(0,13); (*(M2[183]))[185] = M1(0,14); (*(M2[183]))[188] = M1(0,15); (*(M2[183]))[192] = M1(0,16); (*(M2[183]))[193] = M1(0,17); (*(M2[183]))[196] = M1(0,18); (*(M2[183]))[200] = M1(0,19); (*(M2[183]))[321] = M1(0,24); (*(M2[183]))[322] = M1(0,25); (*(M2[183]))[325] = M1(0,26); (*(M2[183]))[331] = M1(0,27); (*(M2[184]))[161] = M1(1,1); (*(M2[184]))[166] = M1(1,4); (*(M2[184]))[167] = M1(1,5); (*(M2[184]))[168] = M1(1,6); (*(M2[184]))[171] = M1(1,7); (*(M2[184]))[172] = M1(1,8); (*(M2[184]))[175] = M1(1,9); (*(M2[184]))[179] = M1(1,10); (*(M2[184]))[180] = M1(1,11); (*(M2[184]))[181] = M1(1,12); (*(M2[184]))[184] = M1(1,13); (*(M2[184]))[185] = M1(1,14); (*(M2[184]))[188] = M1(1,15); (*(M2[184]))[192] = M1(1,16); (*(M2[184]))[193] = M1(1,17); (*(M2[184]))[196] = M1(1,18); (*(M2[184]))[200] = M1(1,19); (*(M2[184]))[321] = M1(1,24); (*(M2[184]))[322] = M1(1,25); (*(M2[184]))[325] = M1(1,26); (*(M2[184]))[331] = M1(1,27); (*(M2[185]))[162] = M1(2,2); (*(M2[185]))[166] = M1(2,4); (*(M2[185]))[167] = M1(2,5); (*(M2[185]))[168] = M1(2,6); (*(M2[185]))[171] = M1(2,7); (*(M2[185]))[172] = M1(2,8); (*(M2[185]))[175] = M1(2,9); (*(M2[185]))[179] = M1(2,10); (*(M2[185]))[180] = M1(2,11); (*(M2[185]))[181] = M1(2,12); (*(M2[185]))[184] = M1(2,13); (*(M2[185]))[185] = M1(2,14); (*(M2[185]))[188] = M1(2,15); (*(M2[185]))[192] = M1(2,16); (*(M2[185]))[193] = M1(2,17); (*(M2[185]))[196] = M1(2,18); (*(M2[185]))[200] = M1(2,19); (*(M2[185]))[321] = M1(2,24); (*(M2[185]))[322] = M1(2,25); (*(M2[185]))[325] = M1(2,26); (*(M2[185]))[331] = M1(2,27); (*(M2[186]))[163] = M1(3,3); (*(M2[186]))[166] = M1(3,4); (*(M2[186]))[167] = M1(3,5); (*(M2[186]))[168] = M1(3,6); (*(M2[186]))[171] = M1(3,7); (*(M2[186]))[172] = M1(3,8); (*(M2[186]))[175] = M1(3,9); (*(M2[186]))[179] = M1(3,10); (*(M2[186]))[180] = M1(3,11); (*(M2[186]))[181] = M1(3,12); (*(M2[186]))[184] = M1(3,13); (*(M2[186]))[185] = M1(3,14); (*(M2[186]))[188] = M1(3,15); (*(M2[186]))[192] = M1(3,16); (*(M2[186]))[193] = M1(3,17); (*(M2[186]))[196] = M1(3,18); (*(M2[186]))[200] = M1(3,19); (*(M2[186]))[321] = M1(3,24); (*(M2[186]))[322] = M1(3,25); (*(M2[186]))[325] = M1(3,26); (*(M2[186]))[331] = M1(3,27); (*(M2[187]))[252] = M1(4,20); (*(M2[187]))[254] = M1(4,21); (*(M2[187]))[261] = M1(4,22); (*(M2[187]))[277] = M1(4,23); (*(M2[187]))[366] = M1(4,28); (*(M2[188]))[141] = M1(0,0); (*(M2[188]))[147] = M1(0,4); (*(M2[188]))[148] = M1(0,5); (*(M2[188]))[149] = M1(0,6); (*(M2[188]))[152] = M1(0,7); (*(M2[188]))[153] = M1(0,8); (*(M2[188]))[156] = M1(0,9); (*(M2[188]))[166] = M1(0,10); (*(M2[188]))[167] = M1(0,11); (*(M2[188]))[168] = M1(0,12); (*(M2[188]))[171] = M1(0,13); (*(M2[188]))[172] = M1(0,14); (*(M2[188]))[175] = M1(0,15); (*(M2[188]))[184] = M1(0,16); (*(M2[188]))[185] = M1(0,17); (*(M2[188]))[188] = M1(0,18); (*(M2[188]))[196] = M1(0,19); (*(M2[188]))[311] = M1(0,24); (*(M2[188]))[312] = M1(0,25); (*(M2[188]))[315] = M1(0,26); (*(M2[188]))[325] = M1(0,27); (*(M2[189]))[142] = M1(1,1); (*(M2[189]))[147] = M1(1,4); (*(M2[189]))[148] = M1(1,5); (*(M2[189]))[149] = M1(1,6); (*(M2[189]))[152] = M1(1,7); (*(M2[189]))[153] = M1(1,8); (*(M2[189]))[156] = M1(1,9); (*(M2[189]))[166] = M1(1,10); (*(M2[189]))[167] = M1(1,11); (*(M2[189]))[168] = M1(1,12); (*(M2[189]))[171] = M1(1,13); (*(M2[189]))[172] = M1(1,14); (*(M2[189]))[175] = M1(1,15); (*(M2[189]))[184] = M1(1,16); (*(M2[189]))[185] = M1(1,17); (*(M2[189]))[188] = M1(1,18); (*(M2[189]))[196] = M1(1,19); (*(M2[189]))[311] = M1(1,24); (*(M2[189]))[312] = M1(1,25); (*(M2[189]))[315] = M1(1,26); (*(M2[189]))[325] = M1(1,27); (*(M2[190]))[143] = M1(2,2); (*(M2[190]))[147] = M1(2,4); (*(M2[190]))[148] = M1(2,5); (*(M2[190]))[149] = M1(2,6); (*(M2[190]))[152] = M1(2,7); (*(M2[190]))[153] = M1(2,8); (*(M2[190]))[156] = M1(2,9); (*(M2[190]))[166] = M1(2,10); (*(M2[190]))[167] = M1(2,11); (*(M2[190]))[168] = M1(2,12); (*(M2[190]))[171] = M1(2,13); (*(M2[190]))[172] = M1(2,14); (*(M2[190]))[175] = M1(2,15); (*(M2[190]))[184] = M1(2,16); (*(M2[190]))[185] = M1(2,17); (*(M2[190]))[188] = M1(2,18); (*(M2[190]))[196] = M1(2,19); (*(M2[190]))[311] = M1(2,24); (*(M2[190]))[312] = M1(2,25); (*(M2[190]))[315] = M1(2,26); (*(M2[190]))[325] = M1(2,27); (*(M2[191]))[144] = M1(3,3); (*(M2[191]))[147] = M1(3,4); (*(M2[191]))[148] = M1(3,5); (*(M2[191]))[149] = M1(3,6); (*(M2[191]))[152] = M1(3,7); (*(M2[191]))[153] = M1(3,8); (*(M2[191]))[156] = M1(3,9); (*(M2[191]))[166] = M1(3,10); (*(M2[191]))[167] = M1(3,11); (*(M2[191]))[168] = M1(3,12); (*(M2[191]))[171] = M1(3,13); (*(M2[191]))[172] = M1(3,14); (*(M2[191]))[175] = M1(3,15); (*(M2[191]))[184] = M1(3,16); (*(M2[191]))[185] = M1(3,17); (*(M2[191]))[188] = M1(3,18); (*(M2[191]))[196] = M1(3,19); (*(M2[191]))[311] = M1(3,24); (*(M2[191]))[312] = M1(3,25); (*(M2[191]))[315] = M1(3,26); (*(M2[191]))[325] = M1(3,27); (*(M2[192]))[237] = M1(4,20); (*(M2[192]))[239] = M1(4,21); (*(M2[192]))[246] = M1(4,22); (*(M2[192]))[271] = M1(4,23); (*(M2[192]))[360] = M1(4,28); (*(M2[193]))[115] = M1(0,0); (*(M2[193]))[121] = M1(0,4); (*(M2[193]))[122] = M1(0,5); (*(M2[193]))[123] = M1(0,6); (*(M2[193]))[126] = M1(0,7); (*(M2[193]))[127] = M1(0,8); (*(M2[193]))[130] = M1(0,9); (*(M2[193]))[147] = M1(0,10); (*(M2[193]))[148] = M1(0,11); (*(M2[193]))[149] = M1(0,12); (*(M2[193]))[152] = M1(0,13); (*(M2[193]))[153] = M1(0,14); (*(M2[193]))[156] = M1(0,15); (*(M2[193]))[171] = M1(0,16); (*(M2[193]))[172] = M1(0,17); (*(M2[193]))[175] = M1(0,18); (*(M2[193]))[188] = M1(0,19); (*(M2[193]))[296] = M1(0,24); (*(M2[193]))[297] = M1(0,25); (*(M2[193]))[300] = M1(0,26); (*(M2[193]))[315] = M1(0,27); (*(M2[194]))[116] = M1(1,1); (*(M2[194]))[121] = M1(1,4); (*(M2[194]))[122] = M1(1,5); (*(M2[194]))[123] = M1(1,6); (*(M2[194]))[126] = M1(1,7); (*(M2[194]))[127] = M1(1,8); (*(M2[194]))[130] = M1(1,9); (*(M2[194]))[147] = M1(1,10); (*(M2[194]))[148] = M1(1,11); (*(M2[194]))[149] = M1(1,12); (*(M2[194]))[152] = M1(1,13); (*(M2[194]))[153] = M1(1,14); (*(M2[194]))[156] = M1(1,15); (*(M2[194]))[171] = M1(1,16); (*(M2[194]))[172] = M1(1,17); (*(M2[194]))[175] = M1(1,18); (*(M2[194]))[188] = M1(1,19); (*(M2[194]))[296] = M1(1,24); (*(M2[194]))[297] = M1(1,25); (*(M2[194]))[300] = M1(1,26); (*(M2[194]))[315] = M1(1,27); (*(M2[195]))[117] = M1(2,2); (*(M2[195]))[121] = M1(2,4); (*(M2[195]))[122] = M1(2,5); (*(M2[195]))[123] = M1(2,6); (*(M2[195]))[126] = M1(2,7); (*(M2[195]))[127] = M1(2,8); (*(M2[195]))[130] = M1(2,9); (*(M2[195]))[147] = M1(2,10); (*(M2[195]))[148] = M1(2,11); (*(M2[195]))[149] = M1(2,12); (*(M2[195]))[152] = M1(2,13); (*(M2[195]))[153] = M1(2,14); (*(M2[195]))[156] = M1(2,15); (*(M2[195]))[171] = M1(2,16); (*(M2[195]))[172] = M1(2,17); (*(M2[195]))[175] = M1(2,18); (*(M2[195]))[188] = M1(2,19); (*(M2[195]))[296] = M1(2,24); (*(M2[195]))[297] = M1(2,25); (*(M2[195]))[300] = M1(2,26); (*(M2[195]))[315] = M1(2,27); (*(M2[196]))[118] = M1(3,3); (*(M2[196]))[121] = M1(3,4); (*(M2[196]))[122] = M1(3,5); (*(M2[196]))[123] = M1(3,6); (*(M2[196]))[126] = M1(3,7); (*(M2[196]))[127] = M1(3,8); (*(M2[196]))[130] = M1(3,9); (*(M2[196]))[147] = M1(3,10); (*(M2[196]))[148] = M1(3,11); (*(M2[196]))[149] = M1(3,12); (*(M2[196]))[152] = M1(3,13); (*(M2[196]))[153] = M1(3,14); (*(M2[196]))[156] = M1(3,15); (*(M2[196]))[171] = M1(3,16); (*(M2[196]))[172] = M1(3,17); (*(M2[196]))[175] = M1(3,18); (*(M2[196]))[188] = M1(3,19); (*(M2[196]))[296] = M1(3,24); (*(M2[196]))[297] = M1(3,25); (*(M2[196]))[300] = M1(3,26); (*(M2[196]))[315] = M1(3,27); (*(M2[197]))[216] = M1(4,20); (*(M2[197]))[218] = M1(4,21); (*(M2[197]))[225] = M1(4,22); (*(M2[197]))[261] = M1(4,23); (*(M2[197]))[350] = M1(4,28); (*(M2[198]))[135] = M1(0,0); (*(M2[198]))[142] = M1(0,4); (*(M2[198]))[143] = M1(0,5); (*(M2[198]))[144] = M1(0,6); (*(M2[198]))[148] = M1(0,7); (*(M2[198]))[149] = M1(0,8); (*(M2[198]))[153] = M1(0,9); (*(M2[198]))[161] = M1(0,10); (*(M2[198]))[162] = M1(0,11); (*(M2[198]))[163] = M1(0,12); (*(M2[198]))[167] = M1(0,13); (*(M2[198]))[168] = M1(0,14); (*(M2[198]))[172] = M1(0,15); (*(M2[198]))[180] = M1(0,16); (*(M2[198]))[181] = M1(0,17); (*(M2[198]))[185] = M1(0,18); (*(M2[198]))[193] = M1(0,19); (*(M2[198]))[307] = M1(0,24); (*(M2[198]))[308] = M1(0,25); (*(M2[198]))[312] = M1(0,26); (*(M2[198]))[322] = M1(0,27); (*(M2[199]))[136] = M1(1,1); (*(M2[199]))[142] = M1(1,4); (*(M2[199]))[143] = M1(1,5); (*(M2[199]))[144] = M1(1,6); (*(M2[199]))[148] = M1(1,7); (*(M2[199]))[149] = M1(1,8); (*(M2[199]))[153] = M1(1,9); (*(M2[199]))[161] = M1(1,10); (*(M2[199]))[162] = M1(1,11); (*(M2[199]))[163] = M1(1,12); (*(M2[199]))[167] = M1(1,13); (*(M2[199]))[168] = M1(1,14); (*(M2[199]))[172] = M1(1,15); (*(M2[199]))[180] = M1(1,16); (*(M2[199]))[181] = M1(1,17); (*(M2[199]))[185] = M1(1,18); (*(M2[199]))[193] = M1(1,19); (*(M2[199]))[307] = M1(1,24); (*(M2[199]))[308] = M1(1,25); (*(M2[199]))[312] = M1(1,26); (*(M2[199]))[322] = M1(1,27); (*(M2[200]))[137] = M1(2,2); (*(M2[200]))[142] = M1(2,4); (*(M2[200]))[143] = M1(2,5); (*(M2[200]))[144] = M1(2,6); (*(M2[200]))[148] = M1(2,7); (*(M2[200]))[149] = M1(2,8); (*(M2[200]))[153] = M1(2,9); (*(M2[200]))[161] = M1(2,10); (*(M2[200]))[162] = M1(2,11); (*(M2[200]))[163] = M1(2,12); (*(M2[200]))[167] = M1(2,13); (*(M2[200]))[168] = M1(2,14); (*(M2[200]))[172] = M1(2,15); (*(M2[200]))[180] = M1(2,16); (*(M2[200]))[181] = M1(2,17); (*(M2[200]))[185] = M1(2,18); (*(M2[200]))[193] = M1(2,19); (*(M2[200]))[307] = M1(2,24); (*(M2[200]))[308] = M1(2,25); (*(M2[200]))[312] = M1(2,26); (*(M2[200]))[322] = M1(2,27); (*(M2[201]))[138] = M1(3,3); (*(M2[201]))[142] = M1(3,4); (*(M2[201]))[143] = M1(3,5); (*(M2[201]))[144] = M1(3,6); (*(M2[201]))[148] = M1(3,7); (*(M2[201]))[149] = M1(3,8); (*(M2[201]))[153] = M1(3,9); (*(M2[201]))[161] = M1(3,10); (*(M2[201]))[162] = M1(3,11); (*(M2[201]))[163] = M1(3,12); (*(M2[201]))[167] = M1(3,13); (*(M2[201]))[168] = M1(3,14); (*(M2[201]))[172] = M1(3,15); (*(M2[201]))[180] = M1(3,16); (*(M2[201]))[181] = M1(3,17); (*(M2[201]))[185] = M1(3,18); (*(M2[201]))[193] = M1(3,19); (*(M2[201]))[307] = M1(3,24); (*(M2[201]))[308] = M1(3,25); (*(M2[201]))[312] = M1(3,26); (*(M2[201]))[322] = M1(3,27); (*(M2[202]))[232] = M1(4,20); (*(M2[202]))[234] = M1(4,21); (*(M2[202]))[243] = M1(4,22); (*(M2[202]))[268] = M1(4,23); (*(M2[202]))[357] = M1(4,28); (*(M2[203]))[109] = M1(0,0); (*(M2[203]))[116] = M1(0,4); (*(M2[203]))[117] = M1(0,5); (*(M2[203]))[118] = M1(0,6); (*(M2[203]))[122] = M1(0,7); (*(M2[203]))[123] = M1(0,8); (*(M2[203]))[127] = M1(0,9); (*(M2[203]))[142] = M1(0,10); (*(M2[203]))[143] = M1(0,11); (*(M2[203]))[144] = M1(0,12); (*(M2[203]))[148] = M1(0,13); (*(M2[203]))[149] = M1(0,14); (*(M2[203]))[153] = M1(0,15); (*(M2[203]))[167] = M1(0,16); (*(M2[203]))[168] = M1(0,17); (*(M2[203]))[172] = M1(0,18); (*(M2[203]))[185] = M1(0,19); (*(M2[203]))[292] = M1(0,24); (*(M2[203]))[293] = M1(0,25); (*(M2[203]))[297] = M1(0,26); (*(M2[203]))[312] = M1(0,27); (*(M2[204]))[110] = M1(1,1); (*(M2[204]))[116] = M1(1,4); (*(M2[204]))[117] = M1(1,5); (*(M2[204]))[118] = M1(1,6); (*(M2[204]))[122] = M1(1,7); (*(M2[204]))[123] = M1(1,8); (*(M2[204]))[127] = M1(1,9); (*(M2[204]))[142] = M1(1,10); (*(M2[204]))[143] = M1(1,11); (*(M2[204]))[144] = M1(1,12); (*(M2[204]))[148] = M1(1,13); (*(M2[204]))[149] = M1(1,14); (*(M2[204]))[153] = M1(1,15); (*(M2[204]))[167] = M1(1,16); (*(M2[204]))[168] = M1(1,17); (*(M2[204]))[172] = M1(1,18); (*(M2[204]))[185] = M1(1,19); (*(M2[204]))[292] = M1(1,24); (*(M2[204]))[293] = M1(1,25); (*(M2[204]))[297] = M1(1,26); (*(M2[204]))[312] = M1(1,27); (*(M2[205]))[111] = M1(2,2); (*(M2[205]))[116] = M1(2,4); (*(M2[205]))[117] = M1(2,5); (*(M2[205]))[118] = M1(2,6); (*(M2[205]))[122] = M1(2,7); (*(M2[205]))[123] = M1(2,8); (*(M2[205]))[127] = M1(2,9); (*(M2[205]))[142] = M1(2,10); (*(M2[205]))[143] = M1(2,11); (*(M2[205]))[144] = M1(2,12); (*(M2[205]))[148] = M1(2,13); (*(M2[205]))[149] = M1(2,14); (*(M2[205]))[153] = M1(2,15); (*(M2[205]))[167] = M1(2,16); (*(M2[205]))[168] = M1(2,17); (*(M2[205]))[172] = M1(2,18); (*(M2[205]))[185] = M1(2,19); (*(M2[205]))[292] = M1(2,24); (*(M2[205]))[293] = M1(2,25); (*(M2[205]))[297] = M1(2,26); (*(M2[205]))[312] = M1(2,27); (*(M2[206]))[112] = M1(3,3); (*(M2[206]))[116] = M1(3,4); (*(M2[206]))[117] = M1(3,5); (*(M2[206]))[118] = M1(3,6); (*(M2[206]))[122] = M1(3,7); (*(M2[206]))[123] = M1(3,8); (*(M2[206]))[127] = M1(3,9); (*(M2[206]))[142] = M1(3,10); (*(M2[206]))[143] = M1(3,11); (*(M2[206]))[144] = M1(3,12); (*(M2[206]))[148] = M1(3,13); (*(M2[206]))[149] = M1(3,14); (*(M2[206]))[153] = M1(3,15); (*(M2[206]))[167] = M1(3,16); (*(M2[206]))[168] = M1(3,17); (*(M2[206]))[172] = M1(3,18); (*(M2[206]))[185] = M1(3,19); (*(M2[206]))[292] = M1(3,24); (*(M2[206]))[293] = M1(3,25); (*(M2[206]))[297] = M1(3,26); (*(M2[206]))[312] = M1(3,27); (*(M2[207]))[211] = M1(4,20); (*(M2[207]))[213] = M1(4,21); (*(M2[207]))[222] = M1(4,22); (*(M2[207]))[258] = M1(4,23); (*(M2[207]))[347] = M1(4,28); (*(M2[208]))[103] = M1(0,0); (*(M2[208]))[110] = M1(0,4); (*(M2[208]))[111] = M1(0,5); (*(M2[208]))[112] = M1(0,6); (*(M2[208]))[117] = M1(0,7); (*(M2[208]))[118] = M1(0,8); (*(M2[208]))[123] = M1(0,9); (*(M2[208]))[136] = M1(0,10); (*(M2[208]))[137] = M1(0,11); (*(M2[208]))[138] = M1(0,12); (*(M2[208]))[143] = M1(0,13); (*(M2[208]))[144] = M1(0,14); (*(M2[208]))[149] = M1(0,15); (*(M2[208]))[162] = M1(0,16); (*(M2[208]))[163] = M1(0,17); (*(M2[208]))[168] = M1(0,18); (*(M2[208]))[181] = M1(0,19); (*(M2[208]))[287] = M1(0,24); (*(M2[208]))[288] = M1(0,25); (*(M2[208]))[293] = M1(0,26); (*(M2[208]))[308] = M1(0,27); (*(M2[209]))[104] = M1(1,1); (*(M2[209]))[110] = M1(1,4); (*(M2[209]))[111] = M1(1,5); (*(M2[209]))[112] = M1(1,6); (*(M2[209]))[117] = M1(1,7); (*(M2[209]))[118] = M1(1,8); (*(M2[209]))[123] = M1(1,9); (*(M2[209]))[136] = M1(1,10); (*(M2[209]))[137] = M1(1,11); (*(M2[209]))[138] = M1(1,12); (*(M2[209]))[143] = M1(1,13); (*(M2[209]))[144] = M1(1,14); (*(M2[209]))[149] = M1(1,15); (*(M2[209]))[162] = M1(1,16); (*(M2[209]))[163] = M1(1,17); (*(M2[209]))[168] = M1(1,18); (*(M2[209]))[181] = M1(1,19); (*(M2[209]))[287] = M1(1,24); (*(M2[209]))[288] = M1(1,25); (*(M2[209]))[293] = M1(1,26); (*(M2[209]))[308] = M1(1,27); (*(M2[210]))[105] = M1(2,2); (*(M2[210]))[110] = M1(2,4); (*(M2[210]))[111] = M1(2,5); (*(M2[210]))[112] = M1(2,6); (*(M2[210]))[117] = M1(2,7); (*(M2[210]))[118] = M1(2,8); (*(M2[210]))[123] = M1(2,9); (*(M2[210]))[136] = M1(2,10); (*(M2[210]))[137] = M1(2,11); (*(M2[210]))[138] = M1(2,12); (*(M2[210]))[143] = M1(2,13); (*(M2[210]))[144] = M1(2,14); (*(M2[210]))[149] = M1(2,15); (*(M2[210]))[162] = M1(2,16); (*(M2[210]))[163] = M1(2,17); (*(M2[210]))[168] = M1(2,18); (*(M2[210]))[181] = M1(2,19); (*(M2[210]))[287] = M1(2,24); (*(M2[210]))[288] = M1(2,25); (*(M2[210]))[293] = M1(2,26); (*(M2[210]))[308] = M1(2,27); (*(M2[211]))[106] = M1(3,3); (*(M2[211]))[110] = M1(3,4); (*(M2[211]))[111] = M1(3,5); (*(M2[211]))[112] = M1(3,6); (*(M2[211]))[117] = M1(3,7); (*(M2[211]))[118] = M1(3,8); (*(M2[211]))[123] = M1(3,9); (*(M2[211]))[136] = M1(3,10); (*(M2[211]))[137] = M1(3,11); (*(M2[211]))[138] = M1(3,12); (*(M2[211]))[143] = M1(3,13); (*(M2[211]))[144] = M1(3,14); (*(M2[211]))[149] = M1(3,15); (*(M2[211]))[162] = M1(3,16); (*(M2[211]))[163] = M1(3,17); (*(M2[211]))[168] = M1(3,18); (*(M2[211]))[181] = M1(3,19); (*(M2[211]))[287] = M1(3,24); (*(M2[211]))[288] = M1(3,25); (*(M2[211]))[293] = M1(3,26); (*(M2[211]))[308] = M1(3,27); (*(M2[212]))[205] = M1(4,20); (*(M2[212]))[207] = M1(4,21); (*(M2[212]))[218] = M1(4,22); (*(M2[212]))[254] = M1(4,23); (*(M2[212]))[343] = M1(4,28); (*(M2[213]))[134] = M1(0,0); (*(M2[213]))[141] = M1(0,4); (*(M2[213]))[142] = M1(0,5); (*(M2[213]))[143] = M1(0,6); (*(M2[213]))[147] = M1(0,7); (*(M2[213]))[148] = M1(0,8); (*(M2[213]))[152] = M1(0,9); (*(M2[213]))[160] = M1(0,10); (*(M2[213]))[161] = M1(0,11); (*(M2[213]))[162] = M1(0,12); (*(M2[213]))[166] = M1(0,13); (*(M2[213]))[167] = M1(0,14); (*(M2[213]))[171] = M1(0,15); (*(M2[213]))[179] = M1(0,16); (*(M2[213]))[180] = M1(0,17); (*(M2[213]))[184] = M1(0,18); (*(M2[213]))[192] = M1(0,19); (*(M2[213]))[306] = M1(0,24); (*(M2[213]))[307] = M1(0,25); (*(M2[213]))[311] = M1(0,26); (*(M2[213]))[321] = M1(0,27); (*(M2[214]))[135] = M1(1,1); (*(M2[214]))[141] = M1(1,4); (*(M2[214]))[142] = M1(1,5); (*(M2[214]))[143] = M1(1,6); (*(M2[214]))[147] = M1(1,7); (*(M2[214]))[148] = M1(1,8); (*(M2[214]))[152] = M1(1,9); (*(M2[214]))[160] = M1(1,10); (*(M2[214]))[161] = M1(1,11); (*(M2[214]))[162] = M1(1,12); (*(M2[214]))[166] = M1(1,13); (*(M2[214]))[167] = M1(1,14); (*(M2[214]))[171] = M1(1,15); (*(M2[214]))[179] = M1(1,16); (*(M2[214]))[180] = M1(1,17); (*(M2[214]))[184] = M1(1,18); (*(M2[214]))[192] = M1(1,19); (*(M2[214]))[306] = M1(1,24); (*(M2[214]))[307] = M1(1,25); (*(M2[214]))[311] = M1(1,26); (*(M2[214]))[321] = M1(1,27); (*(M2[215]))[136] = M1(2,2); (*(M2[215]))[141] = M1(2,4); (*(M2[215]))[142] = M1(2,5); (*(M2[215]))[143] = M1(2,6); (*(M2[215]))[147] = M1(2,7); (*(M2[215]))[148] = M1(2,8); (*(M2[215]))[152] = M1(2,9); (*(M2[215]))[160] = M1(2,10); (*(M2[215]))[161] = M1(2,11); (*(M2[215]))[162] = M1(2,12); (*(M2[215]))[166] = M1(2,13); (*(M2[215]))[167] = M1(2,14); (*(M2[215]))[171] = M1(2,15); (*(M2[215]))[179] = M1(2,16); (*(M2[215]))[180] = M1(2,17); (*(M2[215]))[184] = M1(2,18); (*(M2[215]))[192] = M1(2,19); (*(M2[215]))[306] = M1(2,24); (*(M2[215]))[307] = M1(2,25); (*(M2[215]))[311] = M1(2,26); (*(M2[215]))[321] = M1(2,27); (*(M2[216]))[137] = M1(3,3); (*(M2[216]))[141] = M1(3,4); (*(M2[216]))[142] = M1(3,5); (*(M2[216]))[143] = M1(3,6); (*(M2[216]))[147] = M1(3,7); (*(M2[216]))[148] = M1(3,8); (*(M2[216]))[152] = M1(3,9); (*(M2[216]))[160] = M1(3,10); (*(M2[216]))[161] = M1(3,11); (*(M2[216]))[162] = M1(3,12); (*(M2[216]))[166] = M1(3,13); (*(M2[216]))[167] = M1(3,14); (*(M2[216]))[171] = M1(3,15); (*(M2[216]))[179] = M1(3,16); (*(M2[216]))[180] = M1(3,17); (*(M2[216]))[184] = M1(3,18); (*(M2[216]))[192] = M1(3,19); (*(M2[216]))[306] = M1(3,24); (*(M2[216]))[307] = M1(3,25); (*(M2[216]))[311] = M1(3,26); (*(M2[216]))[321] = M1(3,27); (*(M2[217]))[231] = M1(4,20); (*(M2[217]))[233] = M1(4,21); (*(M2[217]))[242] = M1(4,22); (*(M2[217]))[267] = M1(4,23); (*(M2[217]))[356] = M1(4,28); (*(M2[218]))[108] = M1(0,0); (*(M2[218]))[115] = M1(0,4); (*(M2[218]))[116] = M1(0,5); (*(M2[218]))[117] = M1(0,6); (*(M2[218]))[121] = M1(0,7); (*(M2[218]))[122] = M1(0,8); (*(M2[218]))[126] = M1(0,9); (*(M2[218]))[141] = M1(0,10); (*(M2[218]))[142] = M1(0,11); (*(M2[218]))[143] = M1(0,12); (*(M2[218]))[147] = M1(0,13); (*(M2[218]))[148] = M1(0,14); (*(M2[218]))[152] = M1(0,15); (*(M2[218]))[166] = M1(0,16); (*(M2[218]))[167] = M1(0,17); (*(M2[218]))[171] = M1(0,18); (*(M2[218]))[184] = M1(0,19); (*(M2[218]))[291] = M1(0,24); (*(M2[218]))[292] = M1(0,25); (*(M2[218]))[296] = M1(0,26); (*(M2[218]))[311] = M1(0,27); (*(M2[219]))[109] = M1(1,1); (*(M2[219]))[115] = M1(1,4); (*(M2[219]))[116] = M1(1,5); (*(M2[219]))[117] = M1(1,6); (*(M2[219]))[121] = M1(1,7); (*(M2[219]))[122] = M1(1,8); (*(M2[219]))[126] = M1(1,9); (*(M2[219]))[141] = M1(1,10); (*(M2[219]))[142] = M1(1,11); (*(M2[219]))[143] = M1(1,12); (*(M2[219]))[147] = M1(1,13); (*(M2[219]))[148] = M1(1,14); (*(M2[219]))[152] = M1(1,15); (*(M2[219]))[166] = M1(1,16); (*(M2[219]))[167] = M1(1,17); (*(M2[219]))[171] = M1(1,18); (*(M2[219]))[184] = M1(1,19); (*(M2[219]))[291] = M1(1,24); (*(M2[219]))[292] = M1(1,25); (*(M2[219]))[296] = M1(1,26); (*(M2[219]))[311] = M1(1,27); (*(M2[220]))[110] = M1(2,2); (*(M2[220]))[115] = M1(2,4); (*(M2[220]))[116] = M1(2,5); (*(M2[220]))[117] = M1(2,6); (*(M2[220]))[121] = M1(2,7); (*(M2[220]))[122] = M1(2,8); (*(M2[220]))[126] = M1(2,9); (*(M2[220]))[141] = M1(2,10); (*(M2[220]))[142] = M1(2,11); (*(M2[220]))[143] = M1(2,12); (*(M2[220]))[147] = M1(2,13); (*(M2[220]))[148] = M1(2,14); (*(M2[220]))[152] = M1(2,15); (*(M2[220]))[166] = M1(2,16); (*(M2[220]))[167] = M1(2,17); (*(M2[220]))[171] = M1(2,18); (*(M2[220]))[184] = M1(2,19); (*(M2[220]))[291] = M1(2,24); (*(M2[220]))[292] = M1(2,25); (*(M2[220]))[296] = M1(2,26); (*(M2[220]))[311] = M1(2,27); (*(M2[221]))[111] = M1(3,3); (*(M2[221]))[115] = M1(3,4); (*(M2[221]))[116] = M1(3,5); (*(M2[221]))[117] = M1(3,6); (*(M2[221]))[121] = M1(3,7); (*(M2[221]))[122] = M1(3,8); (*(M2[221]))[126] = M1(3,9); (*(M2[221]))[141] = M1(3,10); (*(M2[221]))[142] = M1(3,11); (*(M2[221]))[143] = M1(3,12); (*(M2[221]))[147] = M1(3,13); (*(M2[221]))[148] = M1(3,14); (*(M2[221]))[152] = M1(3,15); (*(M2[221]))[166] = M1(3,16); (*(M2[221]))[167] = M1(3,17); (*(M2[221]))[171] = M1(3,18); (*(M2[221]))[184] = M1(3,19); (*(M2[221]))[291] = M1(3,24); (*(M2[221]))[292] = M1(3,25); (*(M2[221]))[296] = M1(3,26); (*(M2[221]))[311] = M1(3,27); (*(M2[222]))[210] = M1(4,20); (*(M2[222]))[212] = M1(4,21); (*(M2[222]))[221] = M1(4,22); (*(M2[222]))[257] = M1(4,23); (*(M2[222]))[346] = M1(4,28); (*(M2[223]))[102] = M1(0,0); (*(M2[223]))[109] = M1(0,4); (*(M2[223]))[110] = M1(0,5); (*(M2[223]))[111] = M1(0,6); (*(M2[223]))[116] = M1(0,7); (*(M2[223]))[117] = M1(0,8); (*(M2[223]))[122] = M1(0,9); (*(M2[223]))[135] = M1(0,10); (*(M2[223]))[136] = M1(0,11); (*(M2[223]))[137] = M1(0,12); (*(M2[223]))[142] = M1(0,13); (*(M2[223]))[143] = M1(0,14); (*(M2[223]))[148] = M1(0,15); (*(M2[223]))[161] = M1(0,16); (*(M2[223]))[162] = M1(0,17); (*(M2[223]))[167] = M1(0,18); (*(M2[223]))[180] = M1(0,19); (*(M2[223]))[286] = M1(0,24); (*(M2[223]))[287] = M1(0,25); (*(M2[223]))[292] = M1(0,26); (*(M2[223]))[307] = M1(0,27); (*(M2[224]))[103] = M1(1,1); (*(M2[224]))[109] = M1(1,4); (*(M2[224]))[110] = M1(1,5); (*(M2[224]))[111] = M1(1,6); (*(M2[224]))[116] = M1(1,7); (*(M2[224]))[117] = M1(1,8); (*(M2[224]))[122] = M1(1,9); (*(M2[224]))[135] = M1(1,10); (*(M2[224]))[136] = M1(1,11); (*(M2[224]))[137] = M1(1,12); (*(M2[224]))[142] = M1(1,13); (*(M2[224]))[143] = M1(1,14); (*(M2[224]))[148] = M1(1,15); (*(M2[224]))[161] = M1(1,16); (*(M2[224]))[162] = M1(1,17); (*(M2[224]))[167] = M1(1,18); (*(M2[224]))[180] = M1(1,19); (*(M2[224]))[286] = M1(1,24); (*(M2[224]))[287] = M1(1,25); (*(M2[224]))[292] = M1(1,26); (*(M2[224]))[307] = M1(1,27); (*(M2[225]))[104] = M1(2,2); (*(M2[225]))[109] = M1(2,4); (*(M2[225]))[110] = M1(2,5); (*(M2[225]))[111] = M1(2,6); (*(M2[225]))[116] = M1(2,7); (*(M2[225]))[117] = M1(2,8); (*(M2[225]))[122] = M1(2,9); (*(M2[225]))[135] = M1(2,10); (*(M2[225]))[136] = M1(2,11); (*(M2[225]))[137] = M1(2,12); (*(M2[225]))[142] = M1(2,13); (*(M2[225]))[143] = M1(2,14); (*(M2[225]))[148] = M1(2,15); (*(M2[225]))[161] = M1(2,16); (*(M2[225]))[162] = M1(2,17); (*(M2[225]))[167] = M1(2,18); (*(M2[225]))[180] = M1(2,19); (*(M2[225]))[286] = M1(2,24); (*(M2[225]))[287] = M1(2,25); (*(M2[225]))[292] = M1(2,26); (*(M2[225]))[307] = M1(2,27); (*(M2[226]))[105] = M1(3,3); (*(M2[226]))[109] = M1(3,4); (*(M2[226]))[110] = M1(3,5); (*(M2[226]))[111] = M1(3,6); (*(M2[226]))[116] = M1(3,7); (*(M2[226]))[117] = M1(3,8); (*(M2[226]))[122] = M1(3,9); (*(M2[226]))[135] = M1(3,10); (*(M2[226]))[136] = M1(3,11); (*(M2[226]))[137] = M1(3,12); (*(M2[226]))[142] = M1(3,13); (*(M2[226]))[143] = M1(3,14); (*(M2[226]))[148] = M1(3,15); (*(M2[226]))[161] = M1(3,16); (*(M2[226]))[162] = M1(3,17); (*(M2[226]))[167] = M1(3,18); (*(M2[226]))[180] = M1(3,19); (*(M2[226]))[286] = M1(3,24); (*(M2[226]))[287] = M1(3,25); (*(M2[226]))[292] = M1(3,26); (*(M2[226]))[307] = M1(3,27); (*(M2[227]))[204] = M1(4,20); (*(M2[227]))[206] = M1(4,21); (*(M2[227]))[217] = M1(4,22); (*(M2[227]))[253] = M1(4,23); (*(M2[227]))[342] = M1(4,28); (*(M2[228]))[101] = M1(0,0); (*(M2[228]))[108] = M1(0,4); (*(M2[228]))[109] = M1(0,5); (*(M2[228]))[110] = M1(0,6); (*(M2[228]))[115] = M1(0,7); (*(M2[228]))[116] = M1(0,8); (*(M2[228]))[121] = M1(0,9); (*(M2[228]))[134] = M1(0,10); (*(M2[228]))[135] = M1(0,11); (*(M2[228]))[136] = M1(0,12); (*(M2[228]))[141] = M1(0,13); (*(M2[228]))[142] = M1(0,14); (*(M2[228]))[147] = M1(0,15); (*(M2[228]))[160] = M1(0,16); (*(M2[228]))[161] = M1(0,17); (*(M2[228]))[166] = M1(0,18); (*(M2[228]))[179] = M1(0,19); (*(M2[228]))[285] = M1(0,24); (*(M2[228]))[286] = M1(0,25); (*(M2[228]))[291] = M1(0,26); (*(M2[228]))[306] = M1(0,27); (*(M2[229]))[102] = M1(1,1); (*(M2[229]))[108] = M1(1,4); (*(M2[229]))[109] = M1(1,5); (*(M2[229]))[110] = M1(1,6); (*(M2[229]))[115] = M1(1,7); (*(M2[229]))[116] = M1(1,8); (*(M2[229]))[121] = M1(1,9); (*(M2[229]))[134] = M1(1,10); (*(M2[229]))[135] = M1(1,11); (*(M2[229]))[136] = M1(1,12); (*(M2[229]))[141] = M1(1,13); (*(M2[229]))[142] = M1(1,14); (*(M2[229]))[147] = M1(1,15); (*(M2[229]))[160] = M1(1,16); (*(M2[229]))[161] = M1(1,17); (*(M2[229]))[166] = M1(1,18); (*(M2[229]))[179] = M1(1,19); (*(M2[229]))[285] = M1(1,24); (*(M2[229]))[286] = M1(1,25); (*(M2[229]))[291] = M1(1,26); (*(M2[229]))[306] = M1(1,27); (*(M2[230]))[103] = M1(2,2); (*(M2[230]))[108] = M1(2,4); (*(M2[230]))[109] = M1(2,5); (*(M2[230]))[110] = M1(2,6); (*(M2[230]))[115] = M1(2,7); (*(M2[230]))[116] = M1(2,8); (*(M2[230]))[121] = M1(2,9); (*(M2[230]))[134] = M1(2,10); (*(M2[230]))[135] = M1(2,11); (*(M2[230]))[136] = M1(2,12); (*(M2[230]))[141] = M1(2,13); (*(M2[230]))[142] = M1(2,14); (*(M2[230]))[147] = M1(2,15); (*(M2[230]))[160] = M1(2,16); (*(M2[230]))[161] = M1(2,17); (*(M2[230]))[166] = M1(2,18); (*(M2[230]))[179] = M1(2,19); (*(M2[230]))[285] = M1(2,24); (*(M2[230]))[286] = M1(2,25); (*(M2[230]))[291] = M1(2,26); (*(M2[230]))[306] = M1(2,27); (*(M2[231]))[104] = M1(3,3); (*(M2[231]))[108] = M1(3,4); (*(M2[231]))[109] = M1(3,5); (*(M2[231]))[110] = M1(3,6); (*(M2[231]))[115] = M1(3,7); (*(M2[231]))[116] = M1(3,8); (*(M2[231]))[121] = M1(3,9); (*(M2[231]))[134] = M1(3,10); (*(M2[231]))[135] = M1(3,11); (*(M2[231]))[136] = M1(3,12); (*(M2[231]))[141] = M1(3,13); (*(M2[231]))[142] = M1(3,14); (*(M2[231]))[147] = M1(3,15); (*(M2[231]))[160] = M1(3,16); (*(M2[231]))[161] = M1(3,17); (*(M2[231]))[166] = M1(3,18); (*(M2[231]))[179] = M1(3,19); (*(M2[231]))[285] = M1(3,24); (*(M2[231]))[286] = M1(3,25); (*(M2[231]))[291] = M1(3,26); (*(M2[231]))[306] = M1(3,27); (*(M2[232]))[203] = M1(4,20); (*(M2[232]))[205] = M1(4,21); (*(M2[232]))[216] = M1(4,22); (*(M2[232]))[252] = M1(4,23); (*(M2[232]))[341] = M1(4,28); (*(M2[233]))[243] = M1(1,1); (*(M2[233]))[246] = M1(1,4); (*(M2[233]))[247] = M1(1,5); (*(M2[233]))[248] = M1(1,6); (*(M2[233]))[249] = M1(1,7); (*(M2[233]))[250] = M1(1,8); (*(M2[233]))[251] = M1(1,9); (*(M2[233]))[261] = M1(1,10); (*(M2[233]))[262] = M1(1,11); (*(M2[233]))[263] = M1(1,12); (*(M2[233]))[264] = M1(1,13); (*(M2[233]))[265] = M1(1,14); (*(M2[233]))[266] = M1(1,15); (*(M2[233]))[274] = M1(1,16); (*(M2[233]))[275] = M1(1,17); (*(M2[233]))[276] = M1(1,18); (*(M2[233]))[282] = M1(1,19); (*(M2[233]))[363] = M1(1,24); (*(M2[233]))[364] = M1(1,25); (*(M2[233]))[365] = M1(1,26); (*(M2[233]))[371] = M1(1,27); (*(M2[234]))[244] = M1(2,2); (*(M2[234]))[246] = M1(2,4); (*(M2[234]))[247] = M1(2,5); (*(M2[234]))[248] = M1(2,6); (*(M2[234]))[249] = M1(2,7); (*(M2[234]))[250] = M1(2,8); (*(M2[234]))[251] = M1(2,9); (*(M2[234]))[261] = M1(2,10); (*(M2[234]))[262] = M1(2,11); (*(M2[234]))[263] = M1(2,12); (*(M2[234]))[264] = M1(2,13); (*(M2[234]))[265] = M1(2,14); (*(M2[234]))[266] = M1(2,15); (*(M2[234]))[274] = M1(2,16); (*(M2[234]))[275] = M1(2,17); (*(M2[234]))[276] = M1(2,18); (*(M2[234]))[282] = M1(2,19); (*(M2[234]))[363] = M1(2,24); (*(M2[234]))[364] = M1(2,25); (*(M2[234]))[365] = M1(2,26); (*(M2[234]))[371] = M1(2,27); (*(M2[235]))[245] = M1(3,3); (*(M2[235]))[246] = M1(3,4); (*(M2[235]))[247] = M1(3,5); (*(M2[235]))[248] = M1(3,6); (*(M2[235]))[249] = M1(3,7); (*(M2[235]))[250] = M1(3,8); (*(M2[235]))[251] = M1(3,9); (*(M2[235]))[261] = M1(3,10); (*(M2[235]))[262] = M1(3,11); (*(M2[235]))[263] = M1(3,12); (*(M2[235]))[264] = M1(3,13); (*(M2[235]))[265] = M1(3,14); (*(M2[235]))[266] = M1(3,15); (*(M2[235]))[274] = M1(3,16); (*(M2[235]))[275] = M1(3,17); (*(M2[235]))[276] = M1(3,18); (*(M2[235]))[282] = M1(3,19); (*(M2[235]))[363] = M1(3,24); (*(M2[235]))[364] = M1(3,25); (*(M2[235]))[365] = M1(3,26); (*(M2[235]))[371] = M1(3,27); (*(M2[236]))[221] = M1(0,0); (*(M2[236]))[225] = M1(0,4); (*(M2[236]))[226] = M1(0,5); (*(M2[236]))[227] = M1(0,6); (*(M2[236]))[228] = M1(0,7); (*(M2[236]))[229] = M1(0,8); (*(M2[236]))[230] = M1(0,9); (*(M2[236]))[246] = M1(0,10); (*(M2[236]))[247] = M1(0,11); (*(M2[236]))[248] = M1(0,12); (*(M2[236]))[249] = M1(0,13); (*(M2[236]))[250] = M1(0,14); (*(M2[236]))[251] = M1(0,15); (*(M2[236]))[264] = M1(0,16); (*(M2[236]))[265] = M1(0,17); (*(M2[236]))[266] = M1(0,18); (*(M2[236]))[276] = M1(0,19); (*(M2[236]))[353] = M1(0,24); (*(M2[236]))[354] = M1(0,25); (*(M2[236]))[355] = M1(0,26); (*(M2[236]))[365] = M1(0,27); (*(M2[237]))[222] = M1(1,1); (*(M2[237]))[225] = M1(1,4); (*(M2[237]))[226] = M1(1,5); (*(M2[237]))[227] = M1(1,6); (*(M2[237]))[228] = M1(1,7); (*(M2[237]))[229] = M1(1,8); (*(M2[237]))[230] = M1(1,9); (*(M2[237]))[246] = M1(1,10); (*(M2[237]))[247] = M1(1,11); (*(M2[237]))[248] = M1(1,12); (*(M2[237]))[249] = M1(1,13); (*(M2[237]))[250] = M1(1,14); (*(M2[237]))[251] = M1(1,15); (*(M2[237]))[264] = M1(1,16); (*(M2[237]))[265] = M1(1,17); (*(M2[237]))[266] = M1(1,18); (*(M2[237]))[276] = M1(1,19); (*(M2[237]))[353] = M1(1,24); (*(M2[237]))[354] = M1(1,25); (*(M2[237]))[355] = M1(1,26); (*(M2[237]))[365] = M1(1,27); (*(M2[238]))[223] = M1(2,2); (*(M2[238]))[225] = M1(2,4); (*(M2[238]))[226] = M1(2,5); (*(M2[238]))[227] = M1(2,6); (*(M2[238]))[228] = M1(2,7); (*(M2[238]))[229] = M1(2,8); (*(M2[238]))[230] = M1(2,9); (*(M2[238]))[246] = M1(2,10); (*(M2[238]))[247] = M1(2,11); (*(M2[238]))[248] = M1(2,12); (*(M2[238]))[249] = M1(2,13); (*(M2[238]))[250] = M1(2,14); (*(M2[238]))[251] = M1(2,15); (*(M2[238]))[264] = M1(2,16); (*(M2[238]))[265] = M1(2,17); (*(M2[238]))[266] = M1(2,18); (*(M2[238]))[276] = M1(2,19); (*(M2[238]))[353] = M1(2,24); (*(M2[238]))[354] = M1(2,25); (*(M2[238]))[355] = M1(2,26); (*(M2[238]))[365] = M1(2,27); (*(M2[239]))[224] = M1(3,3); (*(M2[239]))[225] = M1(3,4); (*(M2[239]))[226] = M1(3,5); (*(M2[239]))[227] = M1(3,6); (*(M2[239]))[228] = M1(3,7); (*(M2[239]))[229] = M1(3,8); (*(M2[239]))[230] = M1(3,9); (*(M2[239]))[246] = M1(3,10); (*(M2[239]))[247] = M1(3,11); (*(M2[239]))[248] = M1(3,12); (*(M2[239]))[249] = M1(3,13); (*(M2[239]))[250] = M1(3,14); (*(M2[239]))[251] = M1(3,15); (*(M2[239]))[264] = M1(3,16); (*(M2[239]))[265] = M1(3,17); (*(M2[239]))[266] = M1(3,18); (*(M2[239]))[276] = M1(3,19); (*(M2[239]))[353] = M1(3,24); (*(M2[239]))[354] = M1(3,25); (*(M2[239]))[355] = M1(3,26); (*(M2[239]))[365] = M1(3,27); (*(M2[240]))[253] = M1(0,0); (*(M2[240]))[258] = M1(0,4); (*(M2[240]))[259] = M1(0,5); (*(M2[240]))[260] = M1(0,6); (*(M2[240]))[262] = M1(0,7); (*(M2[240]))[263] = M1(0,8); (*(M2[240]))[265] = M1(0,9); (*(M2[240]))[268] = M1(0,10); (*(M2[240]))[269] = M1(0,11); (*(M2[240]))[270] = M1(0,12); (*(M2[240]))[272] = M1(0,13); (*(M2[240]))[273] = M1(0,14); (*(M2[240]))[275] = M1(0,15); (*(M2[240]))[278] = M1(0,16); (*(M2[240]))[279] = M1(0,17); (*(M2[240]))[281] = M1(0,18); (*(M2[240]))[284] = M1(0,19); (*(M2[240]))[367] = M1(0,24); (*(M2[240]))[368] = M1(0,25); (*(M2[240]))[370] = M1(0,26); (*(M2[240]))[373] = M1(0,27); (*(M2[241]))[254] = M1(1,1); (*(M2[241]))[258] = M1(1,4); (*(M2[241]))[259] = M1(1,5); (*(M2[241]))[260] = M1(1,6); (*(M2[241]))[262] = M1(1,7); (*(M2[241]))[263] = M1(1,8); (*(M2[241]))[265] = M1(1,9); (*(M2[241]))[268] = M1(1,10); (*(M2[241]))[269] = M1(1,11); (*(M2[241]))[270] = M1(1,12); (*(M2[241]))[272] = M1(1,13); (*(M2[241]))[273] = M1(1,14); (*(M2[241]))[275] = M1(1,15); (*(M2[241]))[278] = M1(1,16); (*(M2[241]))[279] = M1(1,17); (*(M2[241]))[281] = M1(1,18); (*(M2[241]))[284] = M1(1,19); (*(M2[241]))[367] = M1(1,24); (*(M2[241]))[368] = M1(1,25); (*(M2[241]))[370] = M1(1,26); (*(M2[241]))[373] = M1(1,27); (*(M2[242]))[255] = M1(2,2); (*(M2[242]))[258] = M1(2,4); (*(M2[242]))[259] = M1(2,5); (*(M2[242]))[260] = M1(2,6); (*(M2[242]))[262] = M1(2,7); (*(M2[242]))[263] = M1(2,8); (*(M2[242]))[265] = M1(2,9); (*(M2[242]))[268] = M1(2,10); (*(M2[242]))[269] = M1(2,11); (*(M2[242]))[270] = M1(2,12); (*(M2[242]))[272] = M1(2,13); (*(M2[242]))[273] = M1(2,14); (*(M2[242]))[275] = M1(2,15); (*(M2[242]))[278] = M1(2,16); (*(M2[242]))[279] = M1(2,17); (*(M2[242]))[281] = M1(2,18); (*(M2[242]))[284] = M1(2,19); (*(M2[242]))[367] = M1(2,24); (*(M2[242]))[368] = M1(2,25); (*(M2[242]))[370] = M1(2,26); (*(M2[242]))[373] = M1(2,27); (*(M2[243]))[256] = M1(3,3); (*(M2[243]))[258] = M1(3,4); (*(M2[243]))[259] = M1(3,5); (*(M2[243]))[260] = M1(3,6); (*(M2[243]))[262] = M1(3,7); (*(M2[243]))[263] = M1(3,8); (*(M2[243]))[265] = M1(3,9); (*(M2[243]))[268] = M1(3,10); (*(M2[243]))[269] = M1(3,11); (*(M2[243]))[270] = M1(3,12); (*(M2[243]))[272] = M1(3,13); (*(M2[243]))[273] = M1(3,14); (*(M2[243]))[275] = M1(3,15); (*(M2[243]))[278] = M1(3,16); (*(M2[243]))[279] = M1(3,17); (*(M2[243]))[281] = M1(3,18); (*(M2[243]))[284] = M1(3,19); (*(M2[243]))[367] = M1(3,24); (*(M2[243]))[368] = M1(3,25); (*(M2[243]))[370] = M1(3,26); (*(M2[243]))[373] = M1(3,27); (*(M2[244]))[322] = M1(4,20); (*(M2[244]))[324] = M1(4,21); (*(M2[244]))[329] = M1(4,22); (*(M2[244]))[338] = M1(4,23); (*(M2[244]))[398] = M1(4,28); (*(M2[245]))[238] = M1(0,0); (*(M2[245]))[243] = M1(0,4); (*(M2[245]))[244] = M1(0,5); (*(M2[245]))[245] = M1(0,6); (*(M2[245]))[247] = M1(0,7); (*(M2[245]))[248] = M1(0,8); (*(M2[245]))[250] = M1(0,9); (*(M2[245]))[258] = M1(0,10); (*(M2[245]))[259] = M1(0,11); (*(M2[245]))[260] = M1(0,12); (*(M2[245]))[262] = M1(0,13); (*(M2[245]))[263] = M1(0,14); (*(M2[245]))[265] = M1(0,15); (*(M2[245]))[272] = M1(0,16); (*(M2[245]))[273] = M1(0,17); (*(M2[245]))[275] = M1(0,18); (*(M2[245]))[281] = M1(0,19); (*(M2[245]))[361] = M1(0,24); (*(M2[245]))[362] = M1(0,25); (*(M2[245]))[364] = M1(0,26); (*(M2[245]))[370] = M1(0,27); (*(M2[246]))[239] = M1(1,1); (*(M2[246]))[243] = M1(1,4); (*(M2[246]))[244] = M1(1,5); (*(M2[246]))[245] = M1(1,6); (*(M2[246]))[247] = M1(1,7); (*(M2[246]))[248] = M1(1,8); (*(M2[246]))[250] = M1(1,9); (*(M2[246]))[258] = M1(1,10); (*(M2[246]))[259] = M1(1,11); (*(M2[246]))[260] = M1(1,12); (*(M2[246]))[262] = M1(1,13); (*(M2[246]))[263] = M1(1,14); (*(M2[246]))[265] = M1(1,15); (*(M2[246]))[272] = M1(1,16); (*(M2[246]))[273] = M1(1,17); (*(M2[246]))[275] = M1(1,18); (*(M2[246]))[281] = M1(1,19); (*(M2[246]))[361] = M1(1,24); (*(M2[246]))[362] = M1(1,25); (*(M2[246]))[364] = M1(1,26); (*(M2[246]))[370] = M1(1,27); (*(M2[247]))[240] = M1(2,2); (*(M2[247]))[243] = M1(2,4); (*(M2[247]))[244] = M1(2,5); (*(M2[247]))[245] = M1(2,6); (*(M2[247]))[247] = M1(2,7); (*(M2[247]))[248] = M1(2,8); (*(M2[247]))[250] = M1(2,9); (*(M2[247]))[258] = M1(2,10); (*(M2[247]))[259] = M1(2,11); (*(M2[247]))[260] = M1(2,12); (*(M2[247]))[262] = M1(2,13); (*(M2[247]))[263] = M1(2,14); (*(M2[247]))[265] = M1(2,15); (*(M2[247]))[272] = M1(2,16); (*(M2[247]))[273] = M1(2,17); (*(M2[247]))[275] = M1(2,18); (*(M2[247]))[281] = M1(2,19); (*(M2[247]))[361] = M1(2,24); (*(M2[247]))[362] = M1(2,25); (*(M2[247]))[364] = M1(2,26); (*(M2[247]))[370] = M1(2,27); (*(M2[248]))[241] = M1(3,3); (*(M2[248]))[243] = M1(3,4); (*(M2[248]))[244] = M1(3,5); (*(M2[248]))[245] = M1(3,6); (*(M2[248]))[247] = M1(3,7); (*(M2[248]))[248] = M1(3,8); (*(M2[248]))[250] = M1(3,9); (*(M2[248]))[258] = M1(3,10); (*(M2[248]))[259] = M1(3,11); (*(M2[248]))[260] = M1(3,12); (*(M2[248]))[262] = M1(3,13); (*(M2[248]))[263] = M1(3,14); (*(M2[248]))[265] = M1(3,15); (*(M2[248]))[272] = M1(3,16); (*(M2[248]))[273] = M1(3,17); (*(M2[248]))[275] = M1(3,18); (*(M2[248]))[281] = M1(3,19); (*(M2[248]))[361] = M1(3,24); (*(M2[248]))[362] = M1(3,25); (*(M2[248]))[364] = M1(3,26); (*(M2[248]))[370] = M1(3,27); (*(M2[249]))[312] = M1(4,20); (*(M2[249]))[314] = M1(4,21); (*(M2[249]))[319] = M1(4,22); (*(M2[249]))[335] = M1(4,23); (*(M2[249]))[389] = M1(4,28); (*(M2[250]))[217] = M1(0,0); (*(M2[250]))[222] = M1(0,4); (*(M2[250]))[223] = M1(0,5); (*(M2[250]))[224] = M1(0,6); (*(M2[250]))[226] = M1(0,7); (*(M2[250]))[227] = M1(0,8); (*(M2[250]))[229] = M1(0,9); (*(M2[250]))[243] = M1(0,10); (*(M2[250]))[244] = M1(0,11); (*(M2[250]))[245] = M1(0,12); (*(M2[250]))[247] = M1(0,13); (*(M2[250]))[248] = M1(0,14); (*(M2[250]))[250] = M1(0,15); (*(M2[250]))[262] = M1(0,16); (*(M2[250]))[263] = M1(0,17); (*(M2[250]))[265] = M1(0,18); (*(M2[250]))[275] = M1(0,19); (*(M2[250]))[351] = M1(0,24); (*(M2[250]))[352] = M1(0,25); (*(M2[250]))[354] = M1(0,26); (*(M2[250]))[364] = M1(0,27); (*(M2[251]))[218] = M1(1,1); (*(M2[251]))[222] = M1(1,4); (*(M2[251]))[223] = M1(1,5); (*(M2[251]))[224] = M1(1,6); (*(M2[251]))[226] = M1(1,7); (*(M2[251]))[227] = M1(1,8); (*(M2[251]))[229] = M1(1,9); (*(M2[251]))[243] = M1(1,10); (*(M2[251]))[244] = M1(1,11); (*(M2[251]))[245] = M1(1,12); (*(M2[251]))[247] = M1(1,13); (*(M2[251]))[248] = M1(1,14); (*(M2[251]))[250] = M1(1,15); (*(M2[251]))[262] = M1(1,16); (*(M2[251]))[263] = M1(1,17); (*(M2[251]))[265] = M1(1,18); (*(M2[251]))[275] = M1(1,19); (*(M2[251]))[351] = M1(1,24); (*(M2[251]))[352] = M1(1,25); (*(M2[251]))[354] = M1(1,26); (*(M2[251]))[364] = M1(1,27); (*(M2[252]))[219] = M1(2,2); (*(M2[252]))[222] = M1(2,4); (*(M2[252]))[223] = M1(2,5); (*(M2[252]))[224] = M1(2,6); (*(M2[252]))[226] = M1(2,7); (*(M2[252]))[227] = M1(2,8); (*(M2[252]))[229] = M1(2,9); (*(M2[252]))[243] = M1(2,10); (*(M2[252]))[244] = M1(2,11); (*(M2[252]))[245] = M1(2,12); (*(M2[252]))[247] = M1(2,13); (*(M2[252]))[248] = M1(2,14); (*(M2[252]))[250] = M1(2,15); (*(M2[252]))[262] = M1(2,16); (*(M2[252]))[263] = M1(2,17); (*(M2[252]))[265] = M1(2,18); (*(M2[252]))[275] = M1(2,19); (*(M2[252]))[351] = M1(2,24); (*(M2[252]))[352] = M1(2,25); (*(M2[252]))[354] = M1(2,26); (*(M2[252]))[364] = M1(2,27); (*(M2[253]))[220] = M1(3,3); (*(M2[253]))[222] = M1(3,4); (*(M2[253]))[223] = M1(3,5); (*(M2[253]))[224] = M1(3,6); (*(M2[253]))[226] = M1(3,7); (*(M2[253]))[227] = M1(3,8); (*(M2[253]))[229] = M1(3,9); (*(M2[253]))[243] = M1(3,10); (*(M2[253]))[244] = M1(3,11); (*(M2[253]))[245] = M1(3,12); (*(M2[253]))[247] = M1(3,13); (*(M2[253]))[248] = M1(3,14); (*(M2[253]))[250] = M1(3,15); (*(M2[253]))[262] = M1(3,16); (*(M2[253]))[263] = M1(3,17); (*(M2[253]))[265] = M1(3,18); (*(M2[253]))[275] = M1(3,19); (*(M2[253]))[351] = M1(3,24); (*(M2[253]))[352] = M1(3,25); (*(M2[253]))[354] = M1(3,26); (*(M2[253]))[364] = M1(3,27); (*(M2[254]))[297] = M1(4,20); (*(M2[254]))[299] = M1(4,21); (*(M2[254]))[304] = M1(4,22); (*(M2[254]))[329] = M1(4,23); (*(M2[254]))[383] = M1(4,28); (*(M2[255]))[233] = M1(0,0); (*(M2[255]))[239] = M1(0,4); (*(M2[255]))[240] = M1(0,5); (*(M2[255]))[241] = M1(0,6); (*(M2[255]))[244] = M1(0,7); (*(M2[255]))[245] = M1(0,8); (*(M2[255]))[248] = M1(0,9); (*(M2[255]))[254] = M1(0,10); (*(M2[255]))[255] = M1(0,11); (*(M2[255]))[256] = M1(0,12); (*(M2[255]))[259] = M1(0,13); (*(M2[255]))[260] = M1(0,14); (*(M2[255]))[263] = M1(0,15); (*(M2[255]))[269] = M1(0,16); (*(M2[255]))[270] = M1(0,17); (*(M2[255]))[273] = M1(0,18); (*(M2[255]))[279] = M1(0,19); (*(M2[255]))[358] = M1(0,24); (*(M2[255]))[359] = M1(0,25); (*(M2[255]))[362] = M1(0,26); (*(M2[255]))[368] = M1(0,27); (*(M2[256]))[234] = M1(1,1); (*(M2[256]))[239] = M1(1,4); (*(M2[256]))[240] = M1(1,5); (*(M2[256]))[241] = M1(1,6); (*(M2[256]))[244] = M1(1,7); (*(M2[256]))[245] = M1(1,8); (*(M2[256]))[248] = M1(1,9); (*(M2[256]))[254] = M1(1,10); (*(M2[256]))[255] = M1(1,11); (*(M2[256]))[256] = M1(1,12); (*(M2[256]))[259] = M1(1,13); (*(M2[256]))[260] = M1(1,14); (*(M2[256]))[263] = M1(1,15); (*(M2[256]))[269] = M1(1,16); (*(M2[256]))[270] = M1(1,17); (*(M2[256]))[273] = M1(1,18); (*(M2[256]))[279] = M1(1,19); (*(M2[256]))[358] = M1(1,24); (*(M2[256]))[359] = M1(1,25); (*(M2[256]))[362] = M1(1,26); (*(M2[256]))[368] = M1(1,27); (*(M2[257]))[235] = M1(2,2); (*(M2[257]))[239] = M1(2,4); (*(M2[257]))[240] = M1(2,5); (*(M2[257]))[241] = M1(2,6); (*(M2[257]))[244] = M1(2,7); (*(M2[257]))[245] = M1(2,8); (*(M2[257]))[248] = M1(2,9); (*(M2[257]))[254] = M1(2,10); (*(M2[257]))[255] = M1(2,11); (*(M2[257]))[256] = M1(2,12); (*(M2[257]))[259] = M1(2,13); (*(M2[257]))[260] = M1(2,14); (*(M2[257]))[263] = M1(2,15); (*(M2[257]))[269] = M1(2,16); (*(M2[257]))[270] = M1(2,17); (*(M2[257]))[273] = M1(2,18); (*(M2[257]))[279] = M1(2,19); (*(M2[257]))[358] = M1(2,24); (*(M2[257]))[359] = M1(2,25); (*(M2[257]))[362] = M1(2,26); (*(M2[257]))[368] = M1(2,27); (*(M2[258]))[236] = M1(3,3); (*(M2[258]))[239] = M1(3,4); (*(M2[258]))[240] = M1(3,5); (*(M2[258]))[241] = M1(3,6); (*(M2[258]))[244] = M1(3,7); (*(M2[258]))[245] = M1(3,8); (*(M2[258]))[248] = M1(3,9); (*(M2[258]))[254] = M1(3,10); (*(M2[258]))[255] = M1(3,11); (*(M2[258]))[256] = M1(3,12); (*(M2[258]))[259] = M1(3,13); (*(M2[258]))[260] = M1(3,14); (*(M2[258]))[263] = M1(3,15); (*(M2[258]))[269] = M1(3,16); (*(M2[258]))[270] = M1(3,17); (*(M2[258]))[273] = M1(3,18); (*(M2[258]))[279] = M1(3,19); (*(M2[258]))[358] = M1(3,24); (*(M2[258]))[359] = M1(3,25); (*(M2[258]))[362] = M1(3,26); (*(M2[258]))[368] = M1(3,27); (*(M2[259]))[308] = M1(4,20); (*(M2[259]))[310] = M1(4,21); (*(M2[259]))[317] = M1(4,22); (*(M2[259]))[333] = M1(4,23); (*(M2[259]))[387] = M1(4,28); (*(M2[260]))[212] = M1(0,0); (*(M2[260]))[218] = M1(0,4); (*(M2[260]))[219] = M1(0,5); (*(M2[260]))[220] = M1(0,6); (*(M2[260]))[223] = M1(0,7); (*(M2[260]))[224] = M1(0,8); (*(M2[260]))[227] = M1(0,9); (*(M2[260]))[239] = M1(0,10); (*(M2[260]))[240] = M1(0,11); (*(M2[260]))[241] = M1(0,12); (*(M2[260]))[244] = M1(0,13); (*(M2[260]))[245] = M1(0,14); (*(M2[260]))[248] = M1(0,15); (*(M2[260]))[259] = M1(0,16); (*(M2[260]))[260] = M1(0,17); (*(M2[260]))[263] = M1(0,18); (*(M2[260]))[273] = M1(0,19); (*(M2[260]))[348] = M1(0,24); (*(M2[260]))[349] = M1(0,25); (*(M2[260]))[352] = M1(0,26); (*(M2[260]))[362] = M1(0,27); (*(M2[261]))[213] = M1(1,1); (*(M2[261]))[218] = M1(1,4); (*(M2[261]))[219] = M1(1,5); (*(M2[261]))[220] = M1(1,6); (*(M2[261]))[223] = M1(1,7); (*(M2[261]))[224] = M1(1,8); (*(M2[261]))[227] = M1(1,9); (*(M2[261]))[239] = M1(1,10); (*(M2[261]))[240] = M1(1,11); (*(M2[261]))[241] = M1(1,12); (*(M2[261]))[244] = M1(1,13); (*(M2[261]))[245] = M1(1,14); (*(M2[261]))[248] = M1(1,15); (*(M2[261]))[259] = M1(1,16); (*(M2[261]))[260] = M1(1,17); (*(M2[261]))[263] = M1(1,18); (*(M2[261]))[273] = M1(1,19); (*(M2[261]))[348] = M1(1,24); (*(M2[261]))[349] = M1(1,25); (*(M2[261]))[352] = M1(1,26); (*(M2[261]))[362] = M1(1,27); (*(M2[262]))[214] = M1(2,2); (*(M2[262]))[218] = M1(2,4); (*(M2[262]))[219] = M1(2,5); (*(M2[262]))[220] = M1(2,6); (*(M2[262]))[223] = M1(2,7); (*(M2[262]))[224] = M1(2,8); (*(M2[262]))[227] = M1(2,9); (*(M2[262]))[239] = M1(2,10); (*(M2[262]))[240] = M1(2,11); (*(M2[262]))[241] = M1(2,12); (*(M2[262]))[244] = M1(2,13); (*(M2[262]))[245] = M1(2,14); (*(M2[262]))[248] = M1(2,15); (*(M2[262]))[259] = M1(2,16); (*(M2[262]))[260] = M1(2,17); (*(M2[262]))[263] = M1(2,18); (*(M2[262]))[273] = M1(2,19); (*(M2[262]))[348] = M1(2,24); (*(M2[262]))[349] = M1(2,25); (*(M2[262]))[352] = M1(2,26); (*(M2[262]))[362] = M1(2,27); (*(M2[263]))[215] = M1(3,3); (*(M2[263]))[218] = M1(3,4); (*(M2[263]))[219] = M1(3,5); (*(M2[263]))[220] = M1(3,6); (*(M2[263]))[223] = M1(3,7); (*(M2[263]))[224] = M1(3,8); (*(M2[263]))[227] = M1(3,9); (*(M2[263]))[239] = M1(3,10); (*(M2[263]))[240] = M1(3,11); (*(M2[263]))[241] = M1(3,12); (*(M2[263]))[244] = M1(3,13); (*(M2[263]))[245] = M1(3,14); (*(M2[263]))[248] = M1(3,15); (*(M2[263]))[259] = M1(3,16); (*(M2[263]))[260] = M1(3,17); (*(M2[263]))[263] = M1(3,18); (*(M2[263]))[273] = M1(3,19); (*(M2[263]))[348] = M1(3,24); (*(M2[263]))[349] = M1(3,25); (*(M2[263]))[352] = M1(3,26); (*(M2[263]))[362] = M1(3,27); (*(M2[264]))[293] = M1(4,20); (*(M2[264]))[295] = M1(4,21); (*(M2[264]))[302] = M1(4,22); (*(M2[264]))[327] = M1(4,23); (*(M2[264]))[381] = M1(4,28); (*(M2[265]))[206] = M1(0,0); (*(M2[265]))[213] = M1(0,4); (*(M2[265]))[214] = M1(0,5); (*(M2[265]))[215] = M1(0,6); (*(M2[265]))[219] = M1(0,7); (*(M2[265]))[220] = M1(0,8); (*(M2[265]))[224] = M1(0,9); (*(M2[265]))[234] = M1(0,10); (*(M2[265]))[235] = M1(0,11); (*(M2[265]))[236] = M1(0,12); (*(M2[265]))[240] = M1(0,13); (*(M2[265]))[241] = M1(0,14); (*(M2[265]))[245] = M1(0,15); (*(M2[265]))[255] = M1(0,16); (*(M2[265]))[256] = M1(0,17); (*(M2[265]))[260] = M1(0,18); (*(M2[265]))[270] = M1(0,19); (*(M2[265]))[344] = M1(0,24); (*(M2[265]))[345] = M1(0,25); (*(M2[265]))[349] = M1(0,26); (*(M2[265]))[359] = M1(0,27); (*(M2[266]))[207] = M1(1,1); (*(M2[266]))[213] = M1(1,4); (*(M2[266]))[214] = M1(1,5); (*(M2[266]))[215] = M1(1,6); (*(M2[266]))[219] = M1(1,7); (*(M2[266]))[220] = M1(1,8); (*(M2[266]))[224] = M1(1,9); (*(M2[266]))[234] = M1(1,10); (*(M2[266]))[235] = M1(1,11); (*(M2[266]))[236] = M1(1,12); (*(M2[266]))[240] = M1(1,13); (*(M2[266]))[241] = M1(1,14); (*(M2[266]))[245] = M1(1,15); (*(M2[266]))[255] = M1(1,16); (*(M2[266]))[256] = M1(1,17); (*(M2[266]))[260] = M1(1,18); (*(M2[266]))[270] = M1(1,19); (*(M2[266]))[344] = M1(1,24); (*(M2[266]))[345] = M1(1,25); (*(M2[266]))[349] = M1(1,26); (*(M2[266]))[359] = M1(1,27); (*(M2[267]))[208] = M1(2,2); (*(M2[267]))[213] = M1(2,4); (*(M2[267]))[214] = M1(2,5); (*(M2[267]))[215] = M1(2,6); (*(M2[267]))[219] = M1(2,7); (*(M2[267]))[220] = M1(2,8); (*(M2[267]))[224] = M1(2,9); (*(M2[267]))[234] = M1(2,10); (*(M2[267]))[235] = M1(2,11); (*(M2[267]))[236] = M1(2,12); (*(M2[267]))[240] = M1(2,13); (*(M2[267]))[241] = M1(2,14); (*(M2[267]))[245] = M1(2,15); (*(M2[267]))[255] = M1(2,16); (*(M2[267]))[256] = M1(2,17); (*(M2[267]))[260] = M1(2,18); (*(M2[267]))[270] = M1(2,19); (*(M2[267]))[344] = M1(2,24); (*(M2[267]))[345] = M1(2,25); (*(M2[267]))[349] = M1(2,26); (*(M2[267]))[359] = M1(2,27); (*(M2[268]))[209] = M1(3,3); (*(M2[268]))[213] = M1(3,4); (*(M2[268]))[214] = M1(3,5); (*(M2[268]))[215] = M1(3,6); (*(M2[268]))[219] = M1(3,7); (*(M2[268]))[220] = M1(3,8); (*(M2[268]))[224] = M1(3,9); (*(M2[268]))[234] = M1(3,10); (*(M2[268]))[235] = M1(3,11); (*(M2[268]))[236] = M1(3,12); (*(M2[268]))[240] = M1(3,13); (*(M2[268]))[241] = M1(3,14); (*(M2[268]))[245] = M1(3,15); (*(M2[268]))[255] = M1(3,16); (*(M2[268]))[256] = M1(3,17); (*(M2[268]))[260] = M1(3,18); (*(M2[268]))[270] = M1(3,19); (*(M2[268]))[344] = M1(3,24); (*(M2[268]))[345] = M1(3,25); (*(M2[268]))[349] = M1(3,26); (*(M2[268]))[359] = M1(3,27); (*(M2[269]))[288] = M1(4,20); (*(M2[269]))[290] = M1(4,21); (*(M2[269]))[299] = M1(4,22); (*(M2[269]))[324] = M1(4,23); (*(M2[269]))[378] = M1(4,28); (*(M2[270]))[252] = M1(0,0); (*(M2[270]))[257] = M1(0,4); (*(M2[270]))[258] = M1(0,5); (*(M2[270]))[259] = M1(0,6); (*(M2[270]))[261] = M1(0,7); (*(M2[270]))[262] = M1(0,8); (*(M2[270]))[264] = M1(0,9); (*(M2[270]))[267] = M1(0,10); (*(M2[270]))[268] = M1(0,11); (*(M2[270]))[269] = M1(0,12); (*(M2[270]))[271] = M1(0,13); (*(M2[270]))[272] = M1(0,14); (*(M2[270]))[274] = M1(0,15); (*(M2[270]))[277] = M1(0,16); (*(M2[270]))[278] = M1(0,17); (*(M2[270]))[280] = M1(0,18); (*(M2[270]))[283] = M1(0,19); (*(M2[270]))[366] = M1(0,24); (*(M2[270]))[367] = M1(0,25); (*(M2[270]))[369] = M1(0,26); (*(M2[270]))[372] = M1(0,27); (*(M2[271]))[253] = M1(1,1); (*(M2[271]))[257] = M1(1,4); (*(M2[271]))[258] = M1(1,5); (*(M2[271]))[259] = M1(1,6); (*(M2[271]))[261] = M1(1,7); (*(M2[271]))[262] = M1(1,8); (*(M2[271]))[264] = M1(1,9); (*(M2[271]))[267] = M1(1,10); (*(M2[271]))[268] = M1(1,11); (*(M2[271]))[269] = M1(1,12); (*(M2[271]))[271] = M1(1,13); (*(M2[271]))[272] = M1(1,14); (*(M2[271]))[274] = M1(1,15); (*(M2[271]))[277] = M1(1,16); (*(M2[271]))[278] = M1(1,17); (*(M2[271]))[280] = M1(1,18); (*(M2[271]))[283] = M1(1,19); (*(M2[271]))[366] = M1(1,24); (*(M2[271]))[367] = M1(1,25); (*(M2[271]))[369] = M1(1,26); (*(M2[271]))[372] = M1(1,27); (*(M2[272]))[254] = M1(2,2); (*(M2[272]))[257] = M1(2,4); (*(M2[272]))[258] = M1(2,5); (*(M2[272]))[259] = M1(2,6); (*(M2[272]))[261] = M1(2,7); (*(M2[272]))[262] = M1(2,8); (*(M2[272]))[264] = M1(2,9); (*(M2[272]))[267] = M1(2,10); (*(M2[272]))[268] = M1(2,11); (*(M2[272]))[269] = M1(2,12); (*(M2[272]))[271] = M1(2,13); (*(M2[272]))[272] = M1(2,14); (*(M2[272]))[274] = M1(2,15); (*(M2[272]))[277] = M1(2,16); (*(M2[272]))[278] = M1(2,17); (*(M2[272]))[280] = M1(2,18); (*(M2[272]))[283] = M1(2,19); (*(M2[272]))[366] = M1(2,24); (*(M2[272]))[367] = M1(2,25); (*(M2[272]))[369] = M1(2,26); (*(M2[272]))[372] = M1(2,27); (*(M2[273]))[255] = M1(3,3); (*(M2[273]))[257] = M1(3,4); (*(M2[273]))[258] = M1(3,5); (*(M2[273]))[259] = M1(3,6); (*(M2[273]))[261] = M1(3,7); (*(M2[273]))[262] = M1(3,8); (*(M2[273]))[264] = M1(3,9); (*(M2[273]))[267] = M1(3,10); (*(M2[273]))[268] = M1(3,11); (*(M2[273]))[269] = M1(3,12); (*(M2[273]))[271] = M1(3,13); (*(M2[273]))[272] = M1(3,14); (*(M2[273]))[274] = M1(3,15); (*(M2[273]))[277] = M1(3,16); (*(M2[273]))[278] = M1(3,17); (*(M2[273]))[280] = M1(3,18); (*(M2[273]))[283] = M1(3,19); (*(M2[273]))[366] = M1(3,24); (*(M2[273]))[367] = M1(3,25); (*(M2[273]))[369] = M1(3,26); (*(M2[273]))[372] = M1(3,27); (*(M2[274]))[321] = M1(4,20); (*(M2[274]))[323] = M1(4,21); (*(M2[274]))[328] = M1(4,22); (*(M2[274]))[337] = M1(4,23); (*(M2[274]))[397] = M1(4,28); (*(M2[275]))[237] = M1(0,0); (*(M2[275]))[242] = M1(0,4); (*(M2[275]))[243] = M1(0,5); (*(M2[275]))[244] = M1(0,6); (*(M2[275]))[246] = M1(0,7); (*(M2[275]))[247] = M1(0,8); (*(M2[275]))[249] = M1(0,9); (*(M2[275]))[257] = M1(0,10); (*(M2[275]))[258] = M1(0,11); (*(M2[275]))[259] = M1(0,12); (*(M2[275]))[261] = M1(0,13); (*(M2[275]))[262] = M1(0,14); (*(M2[275]))[264] = M1(0,15); (*(M2[275]))[271] = M1(0,16); (*(M2[275]))[272] = M1(0,17); (*(M2[275]))[274] = M1(0,18); (*(M2[275]))[280] = M1(0,19); (*(M2[275]))[360] = M1(0,24); (*(M2[275]))[361] = M1(0,25); (*(M2[275]))[363] = M1(0,26); (*(M2[275]))[369] = M1(0,27); (*(M2[276]))[238] = M1(1,1); (*(M2[276]))[242] = M1(1,4); (*(M2[276]))[243] = M1(1,5); (*(M2[276]))[244] = M1(1,6); (*(M2[276]))[246] = M1(1,7); (*(M2[276]))[247] = M1(1,8); (*(M2[276]))[249] = M1(1,9); (*(M2[276]))[257] = M1(1,10); (*(M2[276]))[258] = M1(1,11); (*(M2[276]))[259] = M1(1,12); (*(M2[276]))[261] = M1(1,13); (*(M2[276]))[262] = M1(1,14); (*(M2[276]))[264] = M1(1,15); (*(M2[276]))[271] = M1(1,16); (*(M2[276]))[272] = M1(1,17); (*(M2[276]))[274] = M1(1,18); (*(M2[276]))[280] = M1(1,19); (*(M2[276]))[360] = M1(1,24); (*(M2[276]))[361] = M1(1,25); (*(M2[276]))[363] = M1(1,26); (*(M2[276]))[369] = M1(1,27); (*(M2[277]))[239] = M1(2,2); (*(M2[277]))[242] = M1(2,4); (*(M2[277]))[243] = M1(2,5); (*(M2[277]))[244] = M1(2,6); (*(M2[277]))[246] = M1(2,7); (*(M2[277]))[247] = M1(2,8); (*(M2[277]))[249] = M1(2,9); (*(M2[277]))[257] = M1(2,10); (*(M2[277]))[258] = M1(2,11); (*(M2[277]))[259] = M1(2,12); (*(M2[277]))[261] = M1(2,13); (*(M2[277]))[262] = M1(2,14); (*(M2[277]))[264] = M1(2,15); (*(M2[277]))[271] = M1(2,16); (*(M2[277]))[272] = M1(2,17); (*(M2[277]))[274] = M1(2,18); (*(M2[277]))[280] = M1(2,19); (*(M2[277]))[360] = M1(2,24); (*(M2[277]))[361] = M1(2,25); (*(M2[277]))[363] = M1(2,26); (*(M2[277]))[369] = M1(2,27); (*(M2[278]))[240] = M1(3,3); (*(M2[278]))[242] = M1(3,4); (*(M2[278]))[243] = M1(3,5); (*(M2[278]))[244] = M1(3,6); (*(M2[278]))[246] = M1(3,7); (*(M2[278]))[247] = M1(3,8); (*(M2[278]))[249] = M1(3,9); (*(M2[278]))[257] = M1(3,10); (*(M2[278]))[258] = M1(3,11); (*(M2[278]))[259] = M1(3,12); (*(M2[278]))[261] = M1(3,13); (*(M2[278]))[262] = M1(3,14); (*(M2[278]))[264] = M1(3,15); (*(M2[278]))[271] = M1(3,16); (*(M2[278]))[272] = M1(3,17); (*(M2[278]))[274] = M1(3,18); (*(M2[278]))[280] = M1(3,19); (*(M2[278]))[360] = M1(3,24); (*(M2[278]))[361] = M1(3,25); (*(M2[278]))[363] = M1(3,26); (*(M2[278]))[369] = M1(3,27); (*(M2[279]))[311] = M1(4,20); (*(M2[279]))[313] = M1(4,21); (*(M2[279]))[318] = M1(4,22); (*(M2[279]))[334] = M1(4,23); (*(M2[279]))[388] = M1(4,28); (*(M2[280]))[216] = M1(0,0); (*(M2[280]))[221] = M1(0,4); (*(M2[280]))[222] = M1(0,5); (*(M2[280]))[223] = M1(0,6); (*(M2[280]))[225] = M1(0,7); (*(M2[280]))[226] = M1(0,8); (*(M2[280]))[228] = M1(0,9); (*(M2[280]))[242] = M1(0,10); (*(M2[280]))[243] = M1(0,11); (*(M2[280]))[244] = M1(0,12); (*(M2[280]))[246] = M1(0,13); (*(M2[280]))[247] = M1(0,14); (*(M2[280]))[249] = M1(0,15); (*(M2[280]))[261] = M1(0,16); (*(M2[280]))[262] = M1(0,17); (*(M2[280]))[264] = M1(0,18); (*(M2[280]))[274] = M1(0,19); (*(M2[280]))[350] = M1(0,24); (*(M2[280]))[351] = M1(0,25); (*(M2[280]))[353] = M1(0,26); (*(M2[280]))[363] = M1(0,27); (*(M2[281]))[217] = M1(1,1); (*(M2[281]))[221] = M1(1,4); (*(M2[281]))[222] = M1(1,5); (*(M2[281]))[223] = M1(1,6); (*(M2[281]))[225] = M1(1,7); (*(M2[281]))[226] = M1(1,8); (*(M2[281]))[228] = M1(1,9); (*(M2[281]))[242] = M1(1,10); (*(M2[281]))[243] = M1(1,11); (*(M2[281]))[244] = M1(1,12); (*(M2[281]))[246] = M1(1,13); (*(M2[281]))[247] = M1(1,14); (*(M2[281]))[249] = M1(1,15); (*(M2[281]))[261] = M1(1,16); (*(M2[281]))[262] = M1(1,17); (*(M2[281]))[264] = M1(1,18); (*(M2[281]))[274] = M1(1,19); (*(M2[281]))[350] = M1(1,24); (*(M2[281]))[351] = M1(1,25); (*(M2[281]))[353] = M1(1,26); (*(M2[281]))[363] = M1(1,27); (*(M2[282]))[218] = M1(2,2); (*(M2[282]))[221] = M1(2,4); (*(M2[282]))[222] = M1(2,5); (*(M2[282]))[223] = M1(2,6); (*(M2[282]))[225] = M1(2,7); (*(M2[282]))[226] = M1(2,8); (*(M2[282]))[228] = M1(2,9); (*(M2[282]))[242] = M1(2,10); (*(M2[282]))[243] = M1(2,11); (*(M2[282]))[244] = M1(2,12); (*(M2[282]))[246] = M1(2,13); (*(M2[282]))[247] = M1(2,14); (*(M2[282]))[249] = M1(2,15); (*(M2[282]))[261] = M1(2,16); (*(M2[282]))[262] = M1(2,17); (*(M2[282]))[264] = M1(2,18); (*(M2[282]))[274] = M1(2,19); (*(M2[282]))[350] = M1(2,24); (*(M2[282]))[351] = M1(2,25); (*(M2[282]))[353] = M1(2,26); (*(M2[282]))[363] = M1(2,27); (*(M2[283]))[219] = M1(3,3); (*(M2[283]))[221] = M1(3,4); (*(M2[283]))[222] = M1(3,5); (*(M2[283]))[223] = M1(3,6); (*(M2[283]))[225] = M1(3,7); (*(M2[283]))[226] = M1(3,8); (*(M2[283]))[228] = M1(3,9); (*(M2[283]))[242] = M1(3,10); (*(M2[283]))[243] = M1(3,11); (*(M2[283]))[244] = M1(3,12); (*(M2[283]))[246] = M1(3,13); (*(M2[283]))[247] = M1(3,14); (*(M2[283]))[249] = M1(3,15); (*(M2[283]))[261] = M1(3,16); (*(M2[283]))[262] = M1(3,17); (*(M2[283]))[264] = M1(3,18); (*(M2[283]))[274] = M1(3,19); (*(M2[283]))[350] = M1(3,24); (*(M2[283]))[351] = M1(3,25); (*(M2[283]))[353] = M1(3,26); (*(M2[283]))[363] = M1(3,27); (*(M2[284]))[296] = M1(4,20); (*(M2[284]))[298] = M1(4,21); (*(M2[284]))[303] = M1(4,22); (*(M2[284]))[328] = M1(4,23); (*(M2[284]))[382] = M1(4,28); (*(M2[285]))[232] = M1(0,0); (*(M2[285]))[238] = M1(0,4); (*(M2[285]))[239] = M1(0,5); (*(M2[285]))[240] = M1(0,6); (*(M2[285]))[243] = M1(0,7); (*(M2[285]))[244] = M1(0,8); (*(M2[285]))[247] = M1(0,9); (*(M2[285]))[253] = M1(0,10); (*(M2[285]))[254] = M1(0,11); (*(M2[285]))[255] = M1(0,12); (*(M2[285]))[258] = M1(0,13); (*(M2[285]))[259] = M1(0,14); (*(M2[285]))[262] = M1(0,15); (*(M2[285]))[268] = M1(0,16); (*(M2[285]))[269] = M1(0,17); (*(M2[285]))[272] = M1(0,18); (*(M2[285]))[278] = M1(0,19); (*(M2[285]))[357] = M1(0,24); (*(M2[285]))[358] = M1(0,25); (*(M2[285]))[361] = M1(0,26); (*(M2[285]))[367] = M1(0,27); (*(M2[286]))[233] = M1(1,1); (*(M2[286]))[238] = M1(1,4); (*(M2[286]))[239] = M1(1,5); (*(M2[286]))[240] = M1(1,6); (*(M2[286]))[243] = M1(1,7); (*(M2[286]))[244] = M1(1,8); (*(M2[286]))[247] = M1(1,9); (*(M2[286]))[253] = M1(1,10); (*(M2[286]))[254] = M1(1,11); (*(M2[286]))[255] = M1(1,12); (*(M2[286]))[258] = M1(1,13); (*(M2[286]))[259] = M1(1,14); (*(M2[286]))[262] = M1(1,15); (*(M2[286]))[268] = M1(1,16); (*(M2[286]))[269] = M1(1,17); (*(M2[286]))[272] = M1(1,18); (*(M2[286]))[278] = M1(1,19); (*(M2[286]))[357] = M1(1,24); (*(M2[286]))[358] = M1(1,25); (*(M2[286]))[361] = M1(1,26); (*(M2[286]))[367] = M1(1,27); (*(M2[287]))[234] = M1(2,2); (*(M2[287]))[238] = M1(2,4); (*(M2[287]))[239] = M1(2,5); (*(M2[287]))[240] = M1(2,6); (*(M2[287]))[243] = M1(2,7); (*(M2[287]))[244] = M1(2,8); (*(M2[287]))[247] = M1(2,9); (*(M2[287]))[253] = M1(2,10); (*(M2[287]))[254] = M1(2,11); (*(M2[287]))[255] = M1(2,12); (*(M2[287]))[258] = M1(2,13); (*(M2[287]))[259] = M1(2,14); (*(M2[287]))[262] = M1(2,15); (*(M2[287]))[268] = M1(2,16); (*(M2[287]))[269] = M1(2,17); (*(M2[287]))[272] = M1(2,18); (*(M2[287]))[278] = M1(2,19); (*(M2[287]))[357] = M1(2,24); (*(M2[287]))[358] = M1(2,25); (*(M2[287]))[361] = M1(2,26); (*(M2[287]))[367] = M1(2,27); (*(M2[288]))[235] = M1(3,3); (*(M2[288]))[238] = M1(3,4); (*(M2[288]))[239] = M1(3,5); (*(M2[288]))[240] = M1(3,6); (*(M2[288]))[243] = M1(3,7); (*(M2[288]))[244] = M1(3,8); (*(M2[288]))[247] = M1(3,9); (*(M2[288]))[253] = M1(3,10); (*(M2[288]))[254] = M1(3,11); (*(M2[288]))[255] = M1(3,12); (*(M2[288]))[258] = M1(3,13); (*(M2[288]))[259] = M1(3,14); (*(M2[288]))[262] = M1(3,15); (*(M2[288]))[268] = M1(3,16); (*(M2[288]))[269] = M1(3,17); (*(M2[288]))[272] = M1(3,18); (*(M2[288]))[278] = M1(3,19); (*(M2[288]))[357] = M1(3,24); (*(M2[288]))[358] = M1(3,25); (*(M2[288]))[361] = M1(3,26); (*(M2[288]))[367] = M1(3,27); (*(M2[289]))[307] = M1(4,20); (*(M2[289]))[309] = M1(4,21); (*(M2[289]))[316] = M1(4,22); (*(M2[289]))[332] = M1(4,23); (*(M2[289]))[386] = M1(4,28); (*(M2[290]))[211] = M1(0,0); (*(M2[290]))[217] = M1(0,4); (*(M2[290]))[218] = M1(0,5); (*(M2[290]))[219] = M1(0,6); (*(M2[290]))[222] = M1(0,7); (*(M2[290]))[223] = M1(0,8); (*(M2[290]))[226] = M1(0,9); (*(M2[290]))[238] = M1(0,10); (*(M2[290]))[239] = M1(0,11); (*(M2[290]))[240] = M1(0,12); (*(M2[290]))[243] = M1(0,13); (*(M2[290]))[244] = M1(0,14); (*(M2[290]))[247] = M1(0,15); (*(M2[290]))[258] = M1(0,16); (*(M2[290]))[259] = M1(0,17); (*(M2[290]))[262] = M1(0,18); (*(M2[290]))[272] = M1(0,19); (*(M2[290]))[347] = M1(0,24); (*(M2[290]))[348] = M1(0,25); (*(M2[290]))[351] = M1(0,26); (*(M2[290]))[361] = M1(0,27); (*(M2[291]))[212] = M1(1,1); (*(M2[291]))[217] = M1(1,4); (*(M2[291]))[218] = M1(1,5); (*(M2[291]))[219] = M1(1,6); (*(M2[291]))[222] = M1(1,7); (*(M2[291]))[223] = M1(1,8); (*(M2[291]))[226] = M1(1,9); (*(M2[291]))[238] = M1(1,10); (*(M2[291]))[239] = M1(1,11); (*(M2[291]))[240] = M1(1,12); (*(M2[291]))[243] = M1(1,13); (*(M2[291]))[244] = M1(1,14); (*(M2[291]))[247] = M1(1,15); (*(M2[291]))[258] = M1(1,16); (*(M2[291]))[259] = M1(1,17); (*(M2[291]))[262] = M1(1,18); (*(M2[291]))[272] = M1(1,19); (*(M2[291]))[347] = M1(1,24); (*(M2[291]))[348] = M1(1,25); (*(M2[291]))[351] = M1(1,26); (*(M2[291]))[361] = M1(1,27); (*(M2[292]))[213] = M1(2,2); (*(M2[292]))[217] = M1(2,4); (*(M2[292]))[218] = M1(2,5); (*(M2[292]))[219] = M1(2,6); (*(M2[292]))[222] = M1(2,7); (*(M2[292]))[223] = M1(2,8); (*(M2[292]))[226] = M1(2,9); (*(M2[292]))[238] = M1(2,10); (*(M2[292]))[239] = M1(2,11); (*(M2[292]))[240] = M1(2,12); (*(M2[292]))[243] = M1(2,13); (*(M2[292]))[244] = M1(2,14); (*(M2[292]))[247] = M1(2,15); (*(M2[292]))[258] = M1(2,16); (*(M2[292]))[259] = M1(2,17); (*(M2[292]))[262] = M1(2,18); (*(M2[292]))[272] = M1(2,19); (*(M2[292]))[347] = M1(2,24); (*(M2[292]))[348] = M1(2,25); (*(M2[292]))[351] = M1(2,26); (*(M2[292]))[361] = M1(2,27); (*(M2[293]))[214] = M1(3,3); (*(M2[293]))[217] = M1(3,4); (*(M2[293]))[218] = M1(3,5); (*(M2[293]))[219] = M1(3,6); (*(M2[293]))[222] = M1(3,7); (*(M2[293]))[223] = M1(3,8); (*(M2[293]))[226] = M1(3,9); (*(M2[293]))[238] = M1(3,10); (*(M2[293]))[239] = M1(3,11); (*(M2[293]))[240] = M1(3,12); (*(M2[293]))[243] = M1(3,13); (*(M2[293]))[244] = M1(3,14); (*(M2[293]))[247] = M1(3,15); (*(M2[293]))[258] = M1(3,16); (*(M2[293]))[259] = M1(3,17); (*(M2[293]))[262] = M1(3,18); (*(M2[293]))[272] = M1(3,19); (*(M2[293]))[347] = M1(3,24); (*(M2[293]))[348] = M1(3,25); (*(M2[293]))[351] = M1(3,26); (*(M2[293]))[361] = M1(3,27); (*(M2[294]))[292] = M1(4,20); (*(M2[294]))[294] = M1(4,21); (*(M2[294]))[301] = M1(4,22); (*(M2[294]))[326] = M1(4,23); (*(M2[294]))[380] = M1(4,28); (*(M2[295]))[205] = M1(0,0); (*(M2[295]))[212] = M1(0,4); (*(M2[295]))[213] = M1(0,5); (*(M2[295]))[214] = M1(0,6); (*(M2[295]))[218] = M1(0,7); (*(M2[295]))[219] = M1(0,8); (*(M2[295]))[223] = M1(0,9); (*(M2[295]))[233] = M1(0,10); (*(M2[295]))[234] = M1(0,11); (*(M2[295]))[235] = M1(0,12); (*(M2[295]))[239] = M1(0,13); (*(M2[295]))[240] = M1(0,14); (*(M2[295]))[244] = M1(0,15); (*(M2[295]))[254] = M1(0,16); (*(M2[295]))[255] = M1(0,17); (*(M2[295]))[259] = M1(0,18); (*(M2[295]))[269] = M1(0,19); (*(M2[295]))[343] = M1(0,24); (*(M2[295]))[344] = M1(0,25); (*(M2[295]))[348] = M1(0,26); (*(M2[295]))[358] = M1(0,27); (*(M2[296]))[206] = M1(1,1); (*(M2[296]))[212] = M1(1,4); (*(M2[296]))[213] = M1(1,5); (*(M2[296]))[214] = M1(1,6); (*(M2[296]))[218] = M1(1,7); (*(M2[296]))[219] = M1(1,8); (*(M2[296]))[223] = M1(1,9); (*(M2[296]))[233] = M1(1,10); (*(M2[296]))[234] = M1(1,11); (*(M2[296]))[235] = M1(1,12); (*(M2[296]))[239] = M1(1,13); (*(M2[296]))[240] = M1(1,14); (*(M2[296]))[244] = M1(1,15); (*(M2[296]))[254] = M1(1,16); (*(M2[296]))[255] = M1(1,17); (*(M2[296]))[259] = M1(1,18); (*(M2[296]))[269] = M1(1,19); (*(M2[296]))[343] = M1(1,24); (*(M2[296]))[344] = M1(1,25); (*(M2[296]))[348] = M1(1,26); (*(M2[296]))[358] = M1(1,27); (*(M2[297]))[207] = M1(2,2); (*(M2[297]))[212] = M1(2,4); (*(M2[297]))[213] = M1(2,5); (*(M2[297]))[214] = M1(2,6); (*(M2[297]))[218] = M1(2,7); (*(M2[297]))[219] = M1(2,8); (*(M2[297]))[223] = M1(2,9); (*(M2[297]))[233] = M1(2,10); (*(M2[297]))[234] = M1(2,11); (*(M2[297]))[235] = M1(2,12); (*(M2[297]))[239] = M1(2,13); (*(M2[297]))[240] = M1(2,14); (*(M2[297]))[244] = M1(2,15); (*(M2[297]))[254] = M1(2,16); (*(M2[297]))[255] = M1(2,17); (*(M2[297]))[259] = M1(2,18); (*(M2[297]))[269] = M1(2,19); (*(M2[297]))[343] = M1(2,24); (*(M2[297]))[344] = M1(2,25); (*(M2[297]))[348] = M1(2,26); (*(M2[297]))[358] = M1(2,27); (*(M2[298]))[208] = M1(3,3); (*(M2[298]))[212] = M1(3,4); (*(M2[298]))[213] = M1(3,5); (*(M2[298]))[214] = M1(3,6); (*(M2[298]))[218] = M1(3,7); (*(M2[298]))[219] = M1(3,8); (*(M2[298]))[223] = M1(3,9); (*(M2[298]))[233] = M1(3,10); (*(M2[298]))[234] = M1(3,11); (*(M2[298]))[235] = M1(3,12); (*(M2[298]))[239] = M1(3,13); (*(M2[298]))[240] = M1(3,14); (*(M2[298]))[244] = M1(3,15); (*(M2[298]))[254] = M1(3,16); (*(M2[298]))[255] = M1(3,17); (*(M2[298]))[259] = M1(3,18); (*(M2[298]))[269] = M1(3,19); (*(M2[298]))[343] = M1(3,24); (*(M2[298]))[344] = M1(3,25); (*(M2[298]))[348] = M1(3,26); (*(M2[298]))[358] = M1(3,27); (*(M2[299]))[287] = M1(4,20); (*(M2[299]))[289] = M1(4,21); (*(M2[299]))[298] = M1(4,22); (*(M2[299]))[323] = M1(4,23); (*(M2[299]))[377] = M1(4,28); (*(M2[300]))[231] = M1(0,0); (*(M2[300]))[237] = M1(0,4); (*(M2[300]))[238] = M1(0,5); (*(M2[300]))[239] = M1(0,6); (*(M2[300]))[242] = M1(0,7); (*(M2[300]))[243] = M1(0,8); (*(M2[300]))[246] = M1(0,9); (*(M2[300]))[252] = M1(0,10); (*(M2[300]))[253] = M1(0,11); (*(M2[300]))[254] = M1(0,12); (*(M2[300]))[257] = M1(0,13); (*(M2[300]))[258] = M1(0,14); (*(M2[300]))[261] = M1(0,15); (*(M2[300]))[267] = M1(0,16); (*(M2[300]))[268] = M1(0,17); (*(M2[300]))[271] = M1(0,18); (*(M2[300]))[277] = M1(0,19); (*(M2[300]))[356] = M1(0,24); (*(M2[300]))[357] = M1(0,25); (*(M2[300]))[360] = M1(0,26); (*(M2[300]))[366] = M1(0,27); (*(M2[301]))[232] = M1(1,1); (*(M2[301]))[237] = M1(1,4); (*(M2[301]))[238] = M1(1,5); (*(M2[301]))[239] = M1(1,6); (*(M2[301]))[242] = M1(1,7); (*(M2[301]))[243] = M1(1,8); (*(M2[301]))[246] = M1(1,9); (*(M2[301]))[252] = M1(1,10); (*(M2[301]))[253] = M1(1,11); (*(M2[301]))[254] = M1(1,12); (*(M2[301]))[257] = M1(1,13); (*(M2[301]))[258] = M1(1,14); (*(M2[301]))[261] = M1(1,15); (*(M2[301]))[267] = M1(1,16); (*(M2[301]))[268] = M1(1,17); (*(M2[301]))[271] = M1(1,18); (*(M2[301]))[277] = M1(1,19); (*(M2[301]))[356] = M1(1,24); (*(M2[301]))[357] = M1(1,25); (*(M2[301]))[360] = M1(1,26); (*(M2[301]))[366] = M1(1,27); (*(M2[302]))[233] = M1(2,2); (*(M2[302]))[237] = M1(2,4); (*(M2[302]))[238] = M1(2,5); (*(M2[302]))[239] = M1(2,6); (*(M2[302]))[242] = M1(2,7); (*(M2[302]))[243] = M1(2,8); (*(M2[302]))[246] = M1(2,9); (*(M2[302]))[252] = M1(2,10); (*(M2[302]))[253] = M1(2,11); (*(M2[302]))[254] = M1(2,12); (*(M2[302]))[257] = M1(2,13); (*(M2[302]))[258] = M1(2,14); (*(M2[302]))[261] = M1(2,15); (*(M2[302]))[267] = M1(2,16); (*(M2[302]))[268] = M1(2,17); (*(M2[302]))[271] = M1(2,18); (*(M2[302]))[277] = M1(2,19); (*(M2[302]))[356] = M1(2,24); (*(M2[302]))[357] = M1(2,25); (*(M2[302]))[360] = M1(2,26); (*(M2[302]))[366] = M1(2,27); (*(M2[303]))[234] = M1(3,3); (*(M2[303]))[237] = M1(3,4); (*(M2[303]))[238] = M1(3,5); (*(M2[303]))[239] = M1(3,6); (*(M2[303]))[242] = M1(3,7); (*(M2[303]))[243] = M1(3,8); (*(M2[303]))[246] = M1(3,9); (*(M2[303]))[252] = M1(3,10); (*(M2[303]))[253] = M1(3,11); (*(M2[303]))[254] = M1(3,12); (*(M2[303]))[257] = M1(3,13); (*(M2[303]))[258] = M1(3,14); (*(M2[303]))[261] = M1(3,15); (*(M2[303]))[267] = M1(3,16); (*(M2[303]))[268] = M1(3,17); (*(M2[303]))[271] = M1(3,18); (*(M2[303]))[277] = M1(3,19); (*(M2[303]))[356] = M1(3,24); (*(M2[303]))[357] = M1(3,25); (*(M2[303]))[360] = M1(3,26); (*(M2[303]))[366] = M1(3,27); (*(M2[304]))[306] = M1(4,20); (*(M2[304]))[308] = M1(4,21); (*(M2[304]))[315] = M1(4,22); (*(M2[304]))[331] = M1(4,23); (*(M2[304]))[385] = M1(4,28); (*(M2[305]))[210] = M1(0,0); (*(M2[305]))[216] = M1(0,4); (*(M2[305]))[217] = M1(0,5); (*(M2[305]))[218] = M1(0,6); (*(M2[305]))[221] = M1(0,7); (*(M2[305]))[222] = M1(0,8); (*(M2[305]))[225] = M1(0,9); (*(M2[305]))[237] = M1(0,10); (*(M2[305]))[238] = M1(0,11); (*(M2[305]))[239] = M1(0,12); (*(M2[305]))[242] = M1(0,13); (*(M2[305]))[243] = M1(0,14); (*(M2[305]))[246] = M1(0,15); (*(M2[305]))[257] = M1(0,16); (*(M2[305]))[258] = M1(0,17); (*(M2[305]))[261] = M1(0,18); (*(M2[305]))[271] = M1(0,19); (*(M2[305]))[346] = M1(0,24); (*(M2[305]))[347] = M1(0,25); (*(M2[305]))[350] = M1(0,26); (*(M2[305]))[360] = M1(0,27); (*(M2[306]))[211] = M1(1,1); (*(M2[306]))[216] = M1(1,4); (*(M2[306]))[217] = M1(1,5); (*(M2[306]))[218] = M1(1,6); (*(M2[306]))[221] = M1(1,7); (*(M2[306]))[222] = M1(1,8); (*(M2[306]))[225] = M1(1,9); (*(M2[306]))[237] = M1(1,10); (*(M2[306]))[238] = M1(1,11); (*(M2[306]))[239] = M1(1,12); (*(M2[306]))[242] = M1(1,13); (*(M2[306]))[243] = M1(1,14); (*(M2[306]))[246] = M1(1,15); (*(M2[306]))[257] = M1(1,16); (*(M2[306]))[258] = M1(1,17); (*(M2[306]))[261] = M1(1,18); (*(M2[306]))[271] = M1(1,19); (*(M2[306]))[346] = M1(1,24); (*(M2[306]))[347] = M1(1,25); (*(M2[306]))[350] = M1(1,26); (*(M2[306]))[360] = M1(1,27); (*(M2[307]))[212] = M1(2,2); (*(M2[307]))[216] = M1(2,4); (*(M2[307]))[217] = M1(2,5); (*(M2[307]))[218] = M1(2,6); (*(M2[307]))[221] = M1(2,7); (*(M2[307]))[222] = M1(2,8); (*(M2[307]))[225] = M1(2,9); (*(M2[307]))[237] = M1(2,10); (*(M2[307]))[238] = M1(2,11); (*(M2[307]))[239] = M1(2,12); (*(M2[307]))[242] = M1(2,13); (*(M2[307]))[243] = M1(2,14); (*(M2[307]))[246] = M1(2,15); (*(M2[307]))[257] = M1(2,16); (*(M2[307]))[258] = M1(2,17); (*(M2[307]))[261] = M1(2,18); (*(M2[307]))[271] = M1(2,19); (*(M2[307]))[346] = M1(2,24); (*(M2[307]))[347] = M1(2,25); (*(M2[307]))[350] = M1(2,26); (*(M2[307]))[360] = M1(2,27); (*(M2[308]))[213] = M1(3,3); (*(M2[308]))[216] = M1(3,4); (*(M2[308]))[217] = M1(3,5); (*(M2[308]))[218] = M1(3,6); (*(M2[308]))[221] = M1(3,7); (*(M2[308]))[222] = M1(3,8); (*(M2[308]))[225] = M1(3,9); (*(M2[308]))[237] = M1(3,10); (*(M2[308]))[238] = M1(3,11); (*(M2[308]))[239] = M1(3,12); (*(M2[308]))[242] = M1(3,13); (*(M2[308]))[243] = M1(3,14); (*(M2[308]))[246] = M1(3,15); (*(M2[308]))[257] = M1(3,16); (*(M2[308]))[258] = M1(3,17); (*(M2[308]))[261] = M1(3,18); (*(M2[308]))[271] = M1(3,19); (*(M2[308]))[346] = M1(3,24); (*(M2[308]))[347] = M1(3,25); (*(M2[308]))[350] = M1(3,26); (*(M2[308]))[360] = M1(3,27); (*(M2[309]))[291] = M1(4,20); (*(M2[309]))[293] = M1(4,21); (*(M2[309]))[300] = M1(4,22); (*(M2[309]))[325] = M1(4,23); (*(M2[309]))[379] = M1(4,28); (*(M2[310]))[204] = M1(0,0); (*(M2[310]))[211] = M1(0,4); (*(M2[310]))[212] = M1(0,5); (*(M2[310]))[213] = M1(0,6); (*(M2[310]))[217] = M1(0,7); (*(M2[310]))[218] = M1(0,8); (*(M2[310]))[222] = M1(0,9); (*(M2[310]))[232] = M1(0,10); (*(M2[310]))[233] = M1(0,11); (*(M2[310]))[234] = M1(0,12); (*(M2[310]))[238] = M1(0,13); (*(M2[310]))[239] = M1(0,14); (*(M2[310]))[243] = M1(0,15); (*(M2[310]))[253] = M1(0,16); (*(M2[310]))[254] = M1(0,17); (*(M2[310]))[258] = M1(0,18); (*(M2[310]))[268] = M1(0,19); (*(M2[310]))[342] = M1(0,24); (*(M2[310]))[343] = M1(0,25); (*(M2[310]))[347] = M1(0,26); (*(M2[310]))[357] = M1(0,27); (*(M2[311]))[205] = M1(1,1); (*(M2[311]))[211] = M1(1,4); (*(M2[311]))[212] = M1(1,5); (*(M2[311]))[213] = M1(1,6); (*(M2[311]))[217] = M1(1,7); (*(M2[311]))[218] = M1(1,8); (*(M2[311]))[222] = M1(1,9); (*(M2[311]))[232] = M1(1,10); (*(M2[311]))[233] = M1(1,11); (*(M2[311]))[234] = M1(1,12); (*(M2[311]))[238] = M1(1,13); (*(M2[311]))[239] = M1(1,14); (*(M2[311]))[243] = M1(1,15); (*(M2[311]))[253] = M1(1,16); (*(M2[311]))[254] = M1(1,17); (*(M2[311]))[258] = M1(1,18); (*(M2[311]))[268] = M1(1,19); (*(M2[311]))[342] = M1(1,24); (*(M2[311]))[343] = M1(1,25); (*(M2[311]))[347] = M1(1,26); (*(M2[311]))[357] = M1(1,27); (*(M2[312]))[206] = M1(2,2); (*(M2[312]))[211] = M1(2,4); (*(M2[312]))[212] = M1(2,5); (*(M2[312]))[213] = M1(2,6); (*(M2[312]))[217] = M1(2,7); (*(M2[312]))[218] = M1(2,8); (*(M2[312]))[222] = M1(2,9); (*(M2[312]))[232] = M1(2,10); (*(M2[312]))[233] = M1(2,11); (*(M2[312]))[234] = M1(2,12); (*(M2[312]))[238] = M1(2,13); (*(M2[312]))[239] = M1(2,14); (*(M2[312]))[243] = M1(2,15); (*(M2[312]))[253] = M1(2,16); (*(M2[312]))[254] = M1(2,17); (*(M2[312]))[258] = M1(2,18); (*(M2[312]))[268] = M1(2,19); (*(M2[312]))[342] = M1(2,24); (*(M2[312]))[343] = M1(2,25); (*(M2[312]))[347] = M1(2,26); (*(M2[312]))[357] = M1(2,27); (*(M2[313]))[207] = M1(3,3); (*(M2[313]))[211] = M1(3,4); (*(M2[313]))[212] = M1(3,5); (*(M2[313]))[213] = M1(3,6); (*(M2[313]))[217] = M1(3,7); (*(M2[313]))[218] = M1(3,8); (*(M2[313]))[222] = M1(3,9); (*(M2[313]))[232] = M1(3,10); (*(M2[313]))[233] = M1(3,11); (*(M2[313]))[234] = M1(3,12); (*(M2[313]))[238] = M1(3,13); (*(M2[313]))[239] = M1(3,14); (*(M2[313]))[243] = M1(3,15); (*(M2[313]))[253] = M1(3,16); (*(M2[313]))[254] = M1(3,17); (*(M2[313]))[258] = M1(3,18); (*(M2[313]))[268] = M1(3,19); (*(M2[313]))[342] = M1(3,24); (*(M2[313]))[343] = M1(3,25); (*(M2[313]))[347] = M1(3,26); (*(M2[313]))[357] = M1(3,27); (*(M2[314]))[286] = M1(4,20); (*(M2[314]))[288] = M1(4,21); (*(M2[314]))[297] = M1(4,22); (*(M2[314]))[322] = M1(4,23); (*(M2[314]))[376] = M1(4,28); (*(M2[315]))[203] = M1(0,0); (*(M2[315]))[210] = M1(0,4); (*(M2[315]))[211] = M1(0,5); (*(M2[315]))[212] = M1(0,6); (*(M2[315]))[216] = M1(0,7); (*(M2[315]))[217] = M1(0,8); (*(M2[315]))[221] = M1(0,9); (*(M2[315]))[231] = M1(0,10); (*(M2[315]))[232] = M1(0,11); (*(M2[315]))[233] = M1(0,12); (*(M2[315]))[237] = M1(0,13); (*(M2[315]))[238] = M1(0,14); (*(M2[315]))[242] = M1(0,15); (*(M2[315]))[252] = M1(0,16); (*(M2[315]))[253] = M1(0,17); (*(M2[315]))[257] = M1(0,18); (*(M2[315]))[267] = M1(0,19); (*(M2[315]))[341] = M1(0,24); (*(M2[315]))[342] = M1(0,25); (*(M2[315]))[346] = M1(0,26); (*(M2[315]))[356] = M1(0,27); (*(M2[316]))[204] = M1(1,1); (*(M2[316]))[210] = M1(1,4); (*(M2[316]))[211] = M1(1,5); (*(M2[316]))[212] = M1(1,6); (*(M2[316]))[216] = M1(1,7); (*(M2[316]))[217] = M1(1,8); (*(M2[316]))[221] = M1(1,9); (*(M2[316]))[231] = M1(1,10); (*(M2[316]))[232] = M1(1,11); (*(M2[316]))[233] = M1(1,12); (*(M2[316]))[237] = M1(1,13); (*(M2[316]))[238] = M1(1,14); (*(M2[316]))[242] = M1(1,15); (*(M2[316]))[252] = M1(1,16); (*(M2[316]))[253] = M1(1,17); (*(M2[316]))[257] = M1(1,18); (*(M2[316]))[267] = M1(1,19); (*(M2[316]))[341] = M1(1,24); (*(M2[316]))[342] = M1(1,25); (*(M2[316]))[346] = M1(1,26); (*(M2[316]))[356] = M1(1,27); (*(M2[317]))[205] = M1(2,2); (*(M2[317]))[210] = M1(2,4); (*(M2[317]))[211] = M1(2,5); (*(M2[317]))[212] = M1(2,6); (*(M2[317]))[216] = M1(2,7); (*(M2[317]))[217] = M1(2,8); (*(M2[317]))[221] = M1(2,9); (*(M2[317]))[231] = M1(2,10); (*(M2[317]))[232] = M1(2,11); (*(M2[317]))[233] = M1(2,12); (*(M2[317]))[237] = M1(2,13); (*(M2[317]))[238] = M1(2,14); (*(M2[317]))[242] = M1(2,15); (*(M2[317]))[252] = M1(2,16); (*(M2[317]))[253] = M1(2,17); (*(M2[317]))[257] = M1(2,18); (*(M2[317]))[267] = M1(2,19); (*(M2[317]))[341] = M1(2,24); (*(M2[317]))[342] = M1(2,25); (*(M2[317]))[346] = M1(2,26); (*(M2[317]))[356] = M1(2,27); (*(M2[318]))[206] = M1(3,3); (*(M2[318]))[210] = M1(3,4); (*(M2[318]))[211] = M1(3,5); (*(M2[318]))[212] = M1(3,6); (*(M2[318]))[216] = M1(3,7); (*(M2[318]))[217] = M1(3,8); (*(M2[318]))[221] = M1(3,9); (*(M2[318]))[231] = M1(3,10); (*(M2[318]))[232] = M1(3,11); (*(M2[318]))[233] = M1(3,12); (*(M2[318]))[237] = M1(3,13); (*(M2[318]))[238] = M1(3,14); (*(M2[318]))[242] = M1(3,15); (*(M2[318]))[252] = M1(3,16); (*(M2[318]))[253] = M1(3,17); (*(M2[318]))[257] = M1(3,18); (*(M2[318]))[267] = M1(3,19); (*(M2[318]))[341] = M1(3,24); (*(M2[318]))[342] = M1(3,25); (*(M2[318]))[346] = M1(3,26); (*(M2[318]))[356] = M1(3,27); (*(M2[319]))[285] = M1(4,20); (*(M2[319]))[287] = M1(4,21); (*(M2[319]))[296] = M1(4,22); (*(M2[319]))[321] = M1(4,23); (*(M2[319]))[375] = M1(4,28); (*(M2[320]))[321] = M1(0,0); (*(M2[320]))[325] = M1(0,4); (*(M2[320]))[326] = M1(0,5); (*(M2[320]))[327] = M1(0,6); (*(M2[320]))[328] = M1(0,7); (*(M2[320]))[329] = M1(0,8); (*(M2[320]))[330] = M1(0,9); (*(M2[320]))[331] = M1(0,10); (*(M2[320]))[332] = M1(0,11); (*(M2[320]))[333] = M1(0,12); (*(M2[320]))[334] = M1(0,13); (*(M2[320]))[335] = M1(0,14); (*(M2[320]))[336] = M1(0,15); (*(M2[320]))[337] = M1(0,16); (*(M2[320]))[338] = M1(0,17); (*(M2[320]))[339] = M1(0,18); (*(M2[320]))[340] = M1(0,19); (*(M2[320]))[397] = M1(0,24); (*(M2[320]))[398] = M1(0,25); (*(M2[320]))[399] = M1(0,26); (*(M2[320]))[400] = M1(0,27); (*(M2[321]))[322] = M1(1,1); (*(M2[321]))[325] = M1(1,4); (*(M2[321]))[326] = M1(1,5); (*(M2[321]))[327] = M1(1,6); (*(M2[321]))[328] = M1(1,7); (*(M2[321]))[329] = M1(1,8); (*(M2[321]))[330] = M1(1,9); (*(M2[321]))[331] = M1(1,10); (*(M2[321]))[332] = M1(1,11); (*(M2[321]))[333] = M1(1,12); (*(M2[321]))[334] = M1(1,13); (*(M2[321]))[335] = M1(1,14); (*(M2[321]))[336] = M1(1,15); (*(M2[321]))[337] = M1(1,16); (*(M2[321]))[338] = M1(1,17); (*(M2[321]))[339] = M1(1,18); (*(M2[321]))[340] = M1(1,19); (*(M2[321]))[397] = M1(1,24); (*(M2[321]))[398] = M1(1,25); (*(M2[321]))[399] = M1(1,26); (*(M2[321]))[400] = M1(1,27); (*(M2[322]))[323] = M1(2,2); (*(M2[322]))[325] = M1(2,4); (*(M2[322]))[326] = M1(2,5); (*(M2[322]))[327] = M1(2,6); (*(M2[322]))[328] = M1(2,7); (*(M2[322]))[329] = M1(2,8); (*(M2[322]))[330] = M1(2,9); (*(M2[322]))[331] = M1(2,10); (*(M2[322]))[332] = M1(2,11); (*(M2[322]))[333] = M1(2,12); (*(M2[322]))[334] = M1(2,13); (*(M2[322]))[335] = M1(2,14); (*(M2[322]))[336] = M1(2,15); (*(M2[322]))[337] = M1(2,16); (*(M2[322]))[338] = M1(2,17); (*(M2[322]))[339] = M1(2,18); (*(M2[322]))[340] = M1(2,19); (*(M2[322]))[397] = M1(2,24); (*(M2[322]))[398] = M1(2,25); (*(M2[322]))[399] = M1(2,26); (*(M2[322]))[400] = M1(2,27); (*(M2[323]))[324] = M1(3,3); (*(M2[323]))[325] = M1(3,4); (*(M2[323]))[326] = M1(3,5); (*(M2[323]))[327] = M1(3,6); (*(M2[323]))[328] = M1(3,7); (*(M2[323]))[329] = M1(3,8); (*(M2[323]))[330] = M1(3,9); (*(M2[323]))[331] = M1(3,10); (*(M2[323]))[332] = M1(3,11); (*(M2[323]))[333] = M1(3,12); (*(M2[323]))[334] = M1(3,13); (*(M2[323]))[335] = M1(3,14); (*(M2[323]))[336] = M1(3,15); (*(M2[323]))[337] = M1(3,16); (*(M2[323]))[338] = M1(3,17); (*(M2[323]))[339] = M1(3,18); (*(M2[323]))[340] = M1(3,19); (*(M2[323]))[397] = M1(3,24); (*(M2[323]))[398] = M1(3,25); (*(M2[323]))[399] = M1(3,26); (*(M2[323]))[400] = M1(3,27); (*(M2[324]))[366] = M1(4,20); (*(M2[324]))[368] = M1(4,21); (*(M2[324]))[371] = M1(4,22); (*(M2[324]))[396] = M1(4,23); (*(M2[324]))[406] = M1(4,28); (*(M2[325]))[311] = M1(0,0); (*(M2[325]))[315] = M1(0,4); (*(M2[325]))[316] = M1(0,5); (*(M2[325]))[317] = M1(0,6); (*(M2[325]))[318] = M1(0,7); (*(M2[325]))[319] = M1(0,8); (*(M2[325]))[320] = M1(0,9); (*(M2[325]))[325] = M1(0,10); (*(M2[325]))[326] = M1(0,11); (*(M2[325]))[327] = M1(0,12); (*(M2[325]))[328] = M1(0,13); (*(M2[325]))[329] = M1(0,14); (*(M2[325]))[330] = M1(0,15); (*(M2[325]))[334] = M1(0,16); (*(M2[325]))[335] = M1(0,17); (*(M2[325]))[336] = M1(0,18); (*(M2[325]))[339] = M1(0,19); (*(M2[325]))[388] = M1(0,24); (*(M2[325]))[389] = M1(0,25); (*(M2[325]))[390] = M1(0,26); (*(M2[325]))[399] = M1(0,27); (*(M2[326]))[312] = M1(1,1); (*(M2[326]))[315] = M1(1,4); (*(M2[326]))[316] = M1(1,5); (*(M2[326]))[317] = M1(1,6); (*(M2[326]))[318] = M1(1,7); (*(M2[326]))[319] = M1(1,8); (*(M2[326]))[320] = M1(1,9); (*(M2[326]))[325] = M1(1,10); (*(M2[326]))[326] = M1(1,11); (*(M2[326]))[327] = M1(1,12); (*(M2[326]))[328] = M1(1,13); (*(M2[326]))[329] = M1(1,14); (*(M2[326]))[330] = M1(1,15); (*(M2[326]))[334] = M1(1,16); (*(M2[326]))[335] = M1(1,17); (*(M2[326]))[336] = M1(1,18); (*(M2[326]))[339] = M1(1,19); (*(M2[326]))[388] = M1(1,24); (*(M2[326]))[389] = M1(1,25); (*(M2[326]))[390] = M1(1,26); (*(M2[326]))[399] = M1(1,27); (*(M2[327]))[313] = M1(2,2); (*(M2[327]))[315] = M1(2,4); (*(M2[327]))[316] = M1(2,5); (*(M2[327]))[317] = M1(2,6); (*(M2[327]))[318] = M1(2,7); (*(M2[327]))[319] = M1(2,8); (*(M2[327]))[320] = M1(2,9); (*(M2[327]))[325] = M1(2,10); (*(M2[327]))[326] = M1(2,11); (*(M2[327]))[327] = M1(2,12); (*(M2[327]))[328] = M1(2,13); (*(M2[327]))[329] = M1(2,14); (*(M2[327]))[330] = M1(2,15); (*(M2[327]))[334] = M1(2,16); (*(M2[327]))[335] = M1(2,17); (*(M2[327]))[336] = M1(2,18); (*(M2[327]))[339] = M1(2,19); (*(M2[327]))[388] = M1(2,24); (*(M2[327]))[389] = M1(2,25); (*(M2[327]))[390] = M1(2,26); (*(M2[327]))[399] = M1(2,27); (*(M2[328]))[314] = M1(3,3); (*(M2[328]))[315] = M1(3,4); (*(M2[328]))[316] = M1(3,5); (*(M2[328]))[317] = M1(3,6); (*(M2[328]))[318] = M1(3,7); (*(M2[328]))[319] = M1(3,8); (*(M2[328]))[320] = M1(3,9); (*(M2[328]))[325] = M1(3,10); (*(M2[328]))[326] = M1(3,11); (*(M2[328]))[327] = M1(3,12); (*(M2[328]))[328] = M1(3,13); (*(M2[328]))[329] = M1(3,14); (*(M2[328]))[330] = M1(3,15); (*(M2[328]))[334] = M1(3,16); (*(M2[328]))[335] = M1(3,17); (*(M2[328]))[336] = M1(3,18); (*(M2[328]))[339] = M1(3,19); (*(M2[328]))[388] = M1(3,24); (*(M2[328]))[389] = M1(3,25); (*(M2[328]))[390] = M1(3,26); (*(M2[328]))[399] = M1(3,27); (*(M2[329]))[360] = M1(4,20); (*(M2[329]))[362] = M1(4,21); (*(M2[329]))[365] = M1(4,22); (*(M2[329]))[374] = M1(4,23); (*(M2[329]))[405] = M1(4,28); (*(M2[330]))[296] = M1(0,0); (*(M2[330]))[300] = M1(0,4); (*(M2[330]))[301] = M1(0,5); (*(M2[330]))[302] = M1(0,6); (*(M2[330]))[303] = M1(0,7); (*(M2[330]))[304] = M1(0,8); (*(M2[330]))[305] = M1(0,9); (*(M2[330]))[315] = M1(0,10); (*(M2[330]))[316] = M1(0,11); (*(M2[330]))[317] = M1(0,12); (*(M2[330]))[318] = M1(0,13); (*(M2[330]))[319] = M1(0,14); (*(M2[330]))[320] = M1(0,15); (*(M2[330]))[328] = M1(0,16); (*(M2[330]))[329] = M1(0,17); (*(M2[330]))[330] = M1(0,18); (*(M2[330]))[336] = M1(0,19); (*(M2[330]))[382] = M1(0,24); (*(M2[330]))[383] = M1(0,25); (*(M2[330]))[384] = M1(0,26); (*(M2[330]))[390] = M1(0,27); (*(M2[331]))[297] = M1(1,1); (*(M2[331]))[300] = M1(1,4); (*(M2[331]))[301] = M1(1,5); (*(M2[331]))[302] = M1(1,6); (*(M2[331]))[303] = M1(1,7); (*(M2[331]))[304] = M1(1,8); (*(M2[331]))[305] = M1(1,9); (*(M2[331]))[315] = M1(1,10); (*(M2[331]))[316] = M1(1,11); (*(M2[331]))[317] = M1(1,12); (*(M2[331]))[318] = M1(1,13); (*(M2[331]))[319] = M1(1,14); (*(M2[331]))[320] = M1(1,15); (*(M2[331]))[328] = M1(1,16); (*(M2[331]))[329] = M1(1,17); (*(M2[331]))[330] = M1(1,18); (*(M2[331]))[336] = M1(1,19); (*(M2[331]))[382] = M1(1,24); (*(M2[331]))[383] = M1(1,25); (*(M2[331]))[384] = M1(1,26); (*(M2[331]))[390] = M1(1,27); (*(M2[332]))[298] = M1(2,2); (*(M2[332]))[300] = M1(2,4); (*(M2[332]))[301] = M1(2,5); (*(M2[332]))[302] = M1(2,6); (*(M2[332]))[303] = M1(2,7); (*(M2[332]))[304] = M1(2,8); (*(M2[332]))[305] = M1(2,9); (*(M2[332]))[315] = M1(2,10); (*(M2[332]))[316] = M1(2,11); (*(M2[332]))[317] = M1(2,12); (*(M2[332]))[318] = M1(2,13); (*(M2[332]))[319] = M1(2,14); (*(M2[332]))[320] = M1(2,15); (*(M2[332]))[328] = M1(2,16); (*(M2[332]))[329] = M1(2,17); (*(M2[332]))[330] = M1(2,18); (*(M2[332]))[336] = M1(2,19); (*(M2[332]))[382] = M1(2,24); (*(M2[332]))[383] = M1(2,25); (*(M2[332]))[384] = M1(2,26); (*(M2[332]))[390] = M1(2,27); (*(M2[333]))[299] = M1(3,3); (*(M2[333]))[300] = M1(3,4); (*(M2[333]))[301] = M1(3,5); (*(M2[333]))[302] = M1(3,6); (*(M2[333]))[303] = M1(3,7); (*(M2[333]))[304] = M1(3,8); (*(M2[333]))[305] = M1(3,9); (*(M2[333]))[315] = M1(3,10); (*(M2[333]))[316] = M1(3,11); (*(M2[333]))[317] = M1(3,12); (*(M2[333]))[318] = M1(3,13); (*(M2[333]))[319] = M1(3,14); (*(M2[333]))[320] = M1(3,15); (*(M2[333]))[328] = M1(3,16); (*(M2[333]))[329] = M1(3,17); (*(M2[333]))[330] = M1(3,18); (*(M2[333]))[336] = M1(3,19); (*(M2[333]))[382] = M1(3,24); (*(M2[333]))[383] = M1(3,25); (*(M2[333]))[384] = M1(3,26); (*(M2[333]))[390] = M1(3,27); (*(M2[334]))[350] = M1(4,20); (*(M2[334]))[352] = M1(4,21); (*(M2[334]))[355] = M1(4,22); (*(M2[334]))[371] = M1(4,23); (*(M2[334]))[402] = M1(4,28); (*(M2[335]))[307] = M1(0,0); (*(M2[335]))[312] = M1(0,4); (*(M2[335]))[313] = M1(0,5); (*(M2[335]))[314] = M1(0,6); (*(M2[335]))[316] = M1(0,7); (*(M2[335]))[317] = M1(0,8); (*(M2[335]))[319] = M1(0,9); (*(M2[335]))[322] = M1(0,10); (*(M2[335]))[323] = M1(0,11); (*(M2[335]))[324] = M1(0,12); (*(M2[335]))[326] = M1(0,13); (*(M2[335]))[327] = M1(0,14); (*(M2[335]))[329] = M1(0,15); (*(M2[335]))[332] = M1(0,16); (*(M2[335]))[333] = M1(0,17); (*(M2[335]))[335] = M1(0,18); (*(M2[335]))[338] = M1(0,19); (*(M2[335]))[386] = M1(0,24); (*(M2[335]))[387] = M1(0,25); (*(M2[335]))[389] = M1(0,26); (*(M2[335]))[398] = M1(0,27); (*(M2[336]))[308] = M1(1,1); (*(M2[336]))[312] = M1(1,4); (*(M2[336]))[313] = M1(1,5); (*(M2[336]))[314] = M1(1,6); (*(M2[336]))[316] = M1(1,7); (*(M2[336]))[317] = M1(1,8); (*(M2[336]))[319] = M1(1,9); (*(M2[336]))[322] = M1(1,10); (*(M2[336]))[323] = M1(1,11); (*(M2[336]))[324] = M1(1,12); (*(M2[336]))[326] = M1(1,13); (*(M2[336]))[327] = M1(1,14); (*(M2[336]))[329] = M1(1,15); (*(M2[336]))[332] = M1(1,16); (*(M2[336]))[333] = M1(1,17); (*(M2[336]))[335] = M1(1,18); (*(M2[336]))[338] = M1(1,19); (*(M2[336]))[386] = M1(1,24); (*(M2[336]))[387] = M1(1,25); (*(M2[336]))[389] = M1(1,26); (*(M2[336]))[398] = M1(1,27); (*(M2[337]))[309] = M1(2,2); (*(M2[337]))[312] = M1(2,4); (*(M2[337]))[313] = M1(2,5); (*(M2[337]))[314] = M1(2,6); (*(M2[337]))[316] = M1(2,7); (*(M2[337]))[317] = M1(2,8); (*(M2[337]))[319] = M1(2,9); (*(M2[337]))[322] = M1(2,10); (*(M2[337]))[323] = M1(2,11); (*(M2[337]))[324] = M1(2,12); (*(M2[337]))[326] = M1(2,13); (*(M2[337]))[327] = M1(2,14); (*(M2[337]))[329] = M1(2,15); (*(M2[337]))[332] = M1(2,16); (*(M2[337]))[333] = M1(2,17); (*(M2[337]))[335] = M1(2,18); (*(M2[337]))[338] = M1(2,19); (*(M2[337]))[386] = M1(2,24); (*(M2[337]))[387] = M1(2,25); (*(M2[337]))[389] = M1(2,26); (*(M2[337]))[398] = M1(2,27); (*(M2[338]))[310] = M1(3,3); (*(M2[338]))[312] = M1(3,4); (*(M2[338]))[313] = M1(3,5); (*(M2[338]))[314] = M1(3,6); (*(M2[338]))[316] = M1(3,7); (*(M2[338]))[317] = M1(3,8); (*(M2[338]))[319] = M1(3,9); (*(M2[338]))[322] = M1(3,10); (*(M2[338]))[323] = M1(3,11); (*(M2[338]))[324] = M1(3,12); (*(M2[338]))[326] = M1(3,13); (*(M2[338]))[327] = M1(3,14); (*(M2[338]))[329] = M1(3,15); (*(M2[338]))[332] = M1(3,16); (*(M2[338]))[333] = M1(3,17); (*(M2[338]))[335] = M1(3,18); (*(M2[338]))[338] = M1(3,19); (*(M2[338]))[386] = M1(3,24); (*(M2[338]))[387] = M1(3,25); (*(M2[338]))[389] = M1(3,26); (*(M2[338]))[398] = M1(3,27); (*(M2[339]))[357] = M1(4,20); (*(M2[339]))[359] = M1(4,21); (*(M2[339]))[364] = M1(4,22); (*(M2[339]))[373] = M1(4,23); (*(M2[339]))[404] = M1(4,28); (*(M2[340]))[292] = M1(0,0); (*(M2[340]))[297] = M1(0,4); (*(M2[340]))[298] = M1(0,5); (*(M2[340]))[299] = M1(0,6); (*(M2[340]))[301] = M1(0,7); (*(M2[340]))[302] = M1(0,8); (*(M2[340]))[304] = M1(0,9); (*(M2[340]))[312] = M1(0,10); (*(M2[340]))[313] = M1(0,11); (*(M2[340]))[314] = M1(0,12); (*(M2[340]))[316] = M1(0,13); (*(M2[340]))[317] = M1(0,14); (*(M2[340]))[319] = M1(0,15); (*(M2[340]))[326] = M1(0,16); (*(M2[340]))[327] = M1(0,17); (*(M2[340]))[329] = M1(0,18); (*(M2[340]))[335] = M1(0,19); (*(M2[340]))[380] = M1(0,24); (*(M2[340]))[381] = M1(0,25); (*(M2[340]))[383] = M1(0,26); (*(M2[340]))[389] = M1(0,27); (*(M2[341]))[293] = M1(1,1); (*(M2[341]))[297] = M1(1,4); (*(M2[341]))[298] = M1(1,5); (*(M2[341]))[299] = M1(1,6); (*(M2[341]))[301] = M1(1,7); (*(M2[341]))[302] = M1(1,8); (*(M2[341]))[304] = M1(1,9); (*(M2[341]))[312] = M1(1,10); (*(M2[341]))[313] = M1(1,11); (*(M2[341]))[314] = M1(1,12); (*(M2[341]))[316] = M1(1,13); (*(M2[341]))[317] = M1(1,14); (*(M2[341]))[319] = M1(1,15); (*(M2[341]))[326] = M1(1,16); (*(M2[341]))[327] = M1(1,17); (*(M2[341]))[329] = M1(1,18); (*(M2[341]))[335] = M1(1,19); (*(M2[341]))[380] = M1(1,24); (*(M2[341]))[381] = M1(1,25); (*(M2[341]))[383] = M1(1,26); (*(M2[341]))[389] = M1(1,27); (*(M2[342]))[294] = M1(2,2); (*(M2[342]))[297] = M1(2,4); (*(M2[342]))[298] = M1(2,5); (*(M2[342]))[299] = M1(2,6); (*(M2[342]))[301] = M1(2,7); (*(M2[342]))[302] = M1(2,8); (*(M2[342]))[304] = M1(2,9); (*(M2[342]))[312] = M1(2,10); (*(M2[342]))[313] = M1(2,11); (*(M2[342]))[314] = M1(2,12); (*(M2[342]))[316] = M1(2,13); (*(M2[342]))[317] = M1(2,14); (*(M2[342]))[319] = M1(2,15); (*(M2[342]))[326] = M1(2,16); (*(M2[342]))[327] = M1(2,17); (*(M2[342]))[329] = M1(2,18); (*(M2[342]))[335] = M1(2,19); (*(M2[342]))[380] = M1(2,24); (*(M2[342]))[381] = M1(2,25); (*(M2[342]))[383] = M1(2,26); (*(M2[342]))[389] = M1(2,27); (*(M2[343]))[295] = M1(3,3); (*(M2[343]))[297] = M1(3,4); (*(M2[343]))[298] = M1(3,5); (*(M2[343]))[299] = M1(3,6); (*(M2[343]))[301] = M1(3,7); (*(M2[343]))[302] = M1(3,8); (*(M2[343]))[304] = M1(3,9); (*(M2[343]))[312] = M1(3,10); (*(M2[343]))[313] = M1(3,11); (*(M2[343]))[314] = M1(3,12); (*(M2[343]))[316] = M1(3,13); (*(M2[343]))[317] = M1(3,14); (*(M2[343]))[319] = M1(3,15); (*(M2[343]))[326] = M1(3,16); (*(M2[343]))[327] = M1(3,17); (*(M2[343]))[329] = M1(3,18); (*(M2[343]))[335] = M1(3,19); (*(M2[343]))[380] = M1(3,24); (*(M2[343]))[381] = M1(3,25); (*(M2[343]))[383] = M1(3,26); (*(M2[343]))[389] = M1(3,27); (*(M2[344]))[347] = M1(4,20); (*(M2[344]))[349] = M1(4,21); (*(M2[344]))[354] = M1(4,22); (*(M2[344]))[370] = M1(4,23); (*(M2[344]))[401] = M1(4,28); (*(M2[345]))[287] = M1(0,0); (*(M2[345]))[293] = M1(0,4); (*(M2[345]))[294] = M1(0,5); (*(M2[345]))[295] = M1(0,6); (*(M2[345]))[298] = M1(0,7); (*(M2[345]))[299] = M1(0,8); (*(M2[345]))[302] = M1(0,9); (*(M2[345]))[308] = M1(0,10); (*(M2[345]))[309] = M1(0,11); (*(M2[345]))[310] = M1(0,12); (*(M2[345]))[313] = M1(0,13); (*(M2[345]))[314] = M1(0,14); (*(M2[345]))[317] = M1(0,15); (*(M2[345]))[323] = M1(0,16); (*(M2[345]))[324] = M1(0,17); (*(M2[345]))[327] = M1(0,18); (*(M2[345]))[333] = M1(0,19); (*(M2[345]))[377] = M1(0,24); (*(M2[345]))[378] = M1(0,25); (*(M2[345]))[381] = M1(0,26); (*(M2[345]))[387] = M1(0,27); (*(M2[346]))[288] = M1(1,1); (*(M2[346]))[293] = M1(1,4); (*(M2[346]))[294] = M1(1,5); (*(M2[346]))[295] = M1(1,6); (*(M2[346]))[298] = M1(1,7); (*(M2[346]))[299] = M1(1,8); (*(M2[346]))[302] = M1(1,9); (*(M2[346]))[308] = M1(1,10); (*(M2[346]))[309] = M1(1,11); (*(M2[346]))[310] = M1(1,12); (*(M2[346]))[313] = M1(1,13); (*(M2[346]))[314] = M1(1,14); (*(M2[346]))[317] = M1(1,15); (*(M2[346]))[323] = M1(1,16); (*(M2[346]))[324] = M1(1,17); (*(M2[346]))[327] = M1(1,18); (*(M2[346]))[333] = M1(1,19); (*(M2[346]))[377] = M1(1,24); (*(M2[346]))[378] = M1(1,25); (*(M2[346]))[381] = M1(1,26); (*(M2[346]))[387] = M1(1,27); (*(M2[347]))[289] = M1(2,2); (*(M2[347]))[293] = M1(2,4); (*(M2[347]))[294] = M1(2,5); (*(M2[347]))[295] = M1(2,6); (*(M2[347]))[298] = M1(2,7); (*(M2[347]))[299] = M1(2,8); (*(M2[347]))[302] = M1(2,9); (*(M2[347]))[308] = M1(2,10); (*(M2[347]))[309] = M1(2,11); (*(M2[347]))[310] = M1(2,12); (*(M2[347]))[313] = M1(2,13); (*(M2[347]))[314] = M1(2,14); (*(M2[347]))[317] = M1(2,15); (*(M2[347]))[323] = M1(2,16); (*(M2[347]))[324] = M1(2,17); (*(M2[347]))[327] = M1(2,18); (*(M2[347]))[333] = M1(2,19); (*(M2[347]))[377] = M1(2,24); (*(M2[347]))[378] = M1(2,25); (*(M2[347]))[381] = M1(2,26); (*(M2[347]))[387] = M1(2,27); (*(M2[348]))[290] = M1(3,3); (*(M2[348]))[293] = M1(3,4); (*(M2[348]))[294] = M1(3,5); (*(M2[348]))[295] = M1(3,6); (*(M2[348]))[298] = M1(3,7); (*(M2[348]))[299] = M1(3,8); (*(M2[348]))[302] = M1(3,9); (*(M2[348]))[308] = M1(3,10); (*(M2[348]))[309] = M1(3,11); (*(M2[348]))[310] = M1(3,12); (*(M2[348]))[313] = M1(3,13); (*(M2[348]))[314] = M1(3,14); (*(M2[348]))[317] = M1(3,15); (*(M2[348]))[323] = M1(3,16); (*(M2[348]))[324] = M1(3,17); (*(M2[348]))[327] = M1(3,18); (*(M2[348]))[333] = M1(3,19); (*(M2[348]))[377] = M1(3,24); (*(M2[348]))[378] = M1(3,25); (*(M2[348]))[381] = M1(3,26); (*(M2[348]))[387] = M1(3,27); (*(M2[349]))[343] = M1(4,20); (*(M2[349]))[345] = M1(4,21); (*(M2[349]))[352] = M1(4,22); (*(M2[349]))[368] = M1(4,23); (*(M2[349]))[393] = M1(4,28); (*(M2[350]))[306] = M1(0,0); (*(M2[350]))[311] = M1(0,4); (*(M2[350]))[312] = M1(0,5); (*(M2[350]))[313] = M1(0,6); (*(M2[350]))[315] = M1(0,7); (*(M2[350]))[316] = M1(0,8); (*(M2[350]))[318] = M1(0,9); (*(M2[350]))[321] = M1(0,10); (*(M2[350]))[322] = M1(0,11); (*(M2[350]))[323] = M1(0,12); (*(M2[350]))[325] = M1(0,13); (*(M2[350]))[326] = M1(0,14); (*(M2[350]))[328] = M1(0,15); (*(M2[350]))[331] = M1(0,16); (*(M2[350]))[332] = M1(0,17); (*(M2[350]))[334] = M1(0,18); (*(M2[350]))[337] = M1(0,19); (*(M2[350]))[385] = M1(0,24); (*(M2[350]))[386] = M1(0,25); (*(M2[350]))[388] = M1(0,26); (*(M2[350]))[397] = M1(0,27); (*(M2[351]))[307] = M1(1,1); (*(M2[351]))[311] = M1(1,4); (*(M2[351]))[312] = M1(1,5); (*(M2[351]))[313] = M1(1,6); (*(M2[351]))[315] = M1(1,7); (*(M2[351]))[316] = M1(1,8); (*(M2[351]))[318] = M1(1,9); (*(M2[351]))[321] = M1(1,10); (*(M2[351]))[322] = M1(1,11); (*(M2[351]))[323] = M1(1,12); (*(M2[351]))[325] = M1(1,13); (*(M2[351]))[326] = M1(1,14); (*(M2[351]))[328] = M1(1,15); (*(M2[351]))[331] = M1(1,16); (*(M2[351]))[332] = M1(1,17); (*(M2[351]))[334] = M1(1,18); (*(M2[351]))[337] = M1(1,19); (*(M2[351]))[385] = M1(1,24); (*(M2[351]))[386] = M1(1,25); (*(M2[351]))[388] = M1(1,26); (*(M2[351]))[397] = M1(1,27); (*(M2[352]))[308] = M1(2,2); (*(M2[352]))[311] = M1(2,4); (*(M2[352]))[312] = M1(2,5); (*(M2[352]))[313] = M1(2,6); (*(M2[352]))[315] = M1(2,7); (*(M2[352]))[316] = M1(2,8); (*(M2[352]))[318] = M1(2,9); (*(M2[352]))[321] = M1(2,10); (*(M2[352]))[322] = M1(2,11); (*(M2[352]))[323] = M1(2,12); (*(M2[352]))[325] = M1(2,13); (*(M2[352]))[326] = M1(2,14); (*(M2[352]))[328] = M1(2,15); (*(M2[352]))[331] = M1(2,16); (*(M2[352]))[332] = M1(2,17); (*(M2[352]))[334] = M1(2,18); (*(M2[352]))[337] = M1(2,19); (*(M2[352]))[385] = M1(2,24); (*(M2[352]))[386] = M1(2,25); (*(M2[352]))[388] = M1(2,26); (*(M2[352]))[397] = M1(2,27); (*(M2[353]))[309] = M1(3,3); (*(M2[353]))[311] = M1(3,4); (*(M2[353]))[312] = M1(3,5); (*(M2[353]))[313] = M1(3,6); (*(M2[353]))[315] = M1(3,7); (*(M2[353]))[316] = M1(3,8); (*(M2[353]))[318] = M1(3,9); (*(M2[353]))[321] = M1(3,10); (*(M2[353]))[322] = M1(3,11); (*(M2[353]))[323] = M1(3,12); (*(M2[353]))[325] = M1(3,13); (*(M2[353]))[326] = M1(3,14); (*(M2[353]))[328] = M1(3,15); (*(M2[353]))[331] = M1(3,16); (*(M2[353]))[332] = M1(3,17); (*(M2[353]))[334] = M1(3,18); (*(M2[353]))[337] = M1(3,19); (*(M2[353]))[385] = M1(3,24); (*(M2[353]))[386] = M1(3,25); (*(M2[353]))[388] = M1(3,26); (*(M2[353]))[397] = M1(3,27); (*(M2[354]))[356] = M1(4,20); (*(M2[354]))[358] = M1(4,21); (*(M2[354]))[363] = M1(4,22); (*(M2[354]))[372] = M1(4,23); (*(M2[354]))[403] = M1(4,28); (*(M2[355]))[291] = M1(0,0); (*(M2[355]))[296] = M1(0,4); (*(M2[355]))[297] = M1(0,5); (*(M2[355]))[298] = M1(0,6); (*(M2[355]))[300] = M1(0,7); (*(M2[355]))[301] = M1(0,8); (*(M2[355]))[303] = M1(0,9); (*(M2[355]))[311] = M1(0,10); (*(M2[355]))[312] = M1(0,11); (*(M2[355]))[313] = M1(0,12); (*(M2[355]))[315] = M1(0,13); (*(M2[355]))[316] = M1(0,14); (*(M2[355]))[318] = M1(0,15); (*(M2[355]))[325] = M1(0,16); (*(M2[355]))[326] = M1(0,17); (*(M2[355]))[328] = M1(0,18); (*(M2[355]))[334] = M1(0,19); (*(M2[355]))[379] = M1(0,24); (*(M2[355]))[380] = M1(0,25); (*(M2[355]))[382] = M1(0,26); (*(M2[355]))[388] = M1(0,27); (*(M2[356]))[292] = M1(1,1); (*(M2[356]))[296] = M1(1,4); (*(M2[356]))[297] = M1(1,5); (*(M2[356]))[298] = M1(1,6); (*(M2[356]))[300] = M1(1,7); (*(M2[356]))[301] = M1(1,8); (*(M2[356]))[303] = M1(1,9); (*(M2[356]))[311] = M1(1,10); (*(M2[356]))[312] = M1(1,11); (*(M2[356]))[313] = M1(1,12); (*(M2[356]))[315] = M1(1,13); (*(M2[356]))[316] = M1(1,14); (*(M2[356]))[318] = M1(1,15); (*(M2[356]))[325] = M1(1,16); (*(M2[356]))[326] = M1(1,17); (*(M2[356]))[328] = M1(1,18); (*(M2[356]))[334] = M1(1,19); (*(M2[356]))[379] = M1(1,24); (*(M2[356]))[380] = M1(1,25); (*(M2[356]))[382] = M1(1,26); (*(M2[356]))[388] = M1(1,27); (*(M2[357]))[293] = M1(2,2); (*(M2[357]))[296] = M1(2,4); (*(M2[357]))[297] = M1(2,5); (*(M2[357]))[298] = M1(2,6); (*(M2[357]))[300] = M1(2,7); (*(M2[357]))[301] = M1(2,8); (*(M2[357]))[303] = M1(2,9); (*(M2[357]))[311] = M1(2,10); (*(M2[357]))[312] = M1(2,11); (*(M2[357]))[313] = M1(2,12); (*(M2[357]))[315] = M1(2,13); (*(M2[357]))[316] = M1(2,14); (*(M2[357]))[318] = M1(2,15); (*(M2[357]))[325] = M1(2,16); (*(M2[357]))[326] = M1(2,17); (*(M2[357]))[328] = M1(2,18); (*(M2[357]))[334] = M1(2,19); (*(M2[357]))[379] = M1(2,24); (*(M2[357]))[380] = M1(2,25); (*(M2[357]))[382] = M1(2,26); (*(M2[357]))[388] = M1(2,27); (*(M2[358]))[294] = M1(3,3); (*(M2[358]))[296] = M1(3,4); (*(M2[358]))[297] = M1(3,5); (*(M2[358]))[298] = M1(3,6); (*(M2[358]))[300] = M1(3,7); (*(M2[358]))[301] = M1(3,8); (*(M2[358]))[303] = M1(3,9); (*(M2[358]))[311] = M1(3,10); (*(M2[358]))[312] = M1(3,11); (*(M2[358]))[313] = M1(3,12); (*(M2[358]))[315] = M1(3,13); (*(M2[358]))[316] = M1(3,14); (*(M2[358]))[318] = M1(3,15); (*(M2[358]))[325] = M1(3,16); (*(M2[358]))[326] = M1(3,17); (*(M2[358]))[328] = M1(3,18); (*(M2[358]))[334] = M1(3,19); (*(M2[358]))[379] = M1(3,24); (*(M2[358]))[380] = M1(3,25); (*(M2[358]))[382] = M1(3,26); (*(M2[358]))[388] = M1(3,27); (*(M2[359]))[346] = M1(4,20); (*(M2[359]))[348] = M1(4,21); (*(M2[359]))[353] = M1(4,22); (*(M2[359]))[369] = M1(4,23); (*(M2[359]))[394] = M1(4,28); (*(M2[360]))[286] = M1(0,0); (*(M2[360]))[292] = M1(0,4); (*(M2[360]))[293] = M1(0,5); (*(M2[360]))[294] = M1(0,6); (*(M2[360]))[297] = M1(0,7); (*(M2[360]))[298] = M1(0,8); (*(M2[360]))[301] = M1(0,9); (*(M2[360]))[307] = M1(0,10); (*(M2[360]))[308] = M1(0,11); (*(M2[360]))[309] = M1(0,12); (*(M2[360]))[312] = M1(0,13); (*(M2[360]))[313] = M1(0,14); (*(M2[360]))[316] = M1(0,15); (*(M2[360]))[322] = M1(0,16); (*(M2[360]))[323] = M1(0,17); (*(M2[360]))[326] = M1(0,18); (*(M2[360]))[332] = M1(0,19); (*(M2[360]))[376] = M1(0,24); (*(M2[360]))[377] = M1(0,25); (*(M2[360]))[380] = M1(0,26); (*(M2[360]))[386] = M1(0,27); (*(M2[361]))[287] = M1(1,1); (*(M2[361]))[292] = M1(1,4); (*(M2[361]))[293] = M1(1,5); (*(M2[361]))[294] = M1(1,6); (*(M2[361]))[297] = M1(1,7); (*(M2[361]))[298] = M1(1,8); (*(M2[361]))[301] = M1(1,9); (*(M2[361]))[307] = M1(1,10); (*(M2[361]))[308] = M1(1,11); (*(M2[361]))[309] = M1(1,12); (*(M2[361]))[312] = M1(1,13); (*(M2[361]))[313] = M1(1,14); (*(M2[361]))[316] = M1(1,15); (*(M2[361]))[322] = M1(1,16); (*(M2[361]))[323] = M1(1,17); (*(M2[361]))[326] = M1(1,18); (*(M2[361]))[332] = M1(1,19); (*(M2[361]))[376] = M1(1,24); (*(M2[361]))[377] = M1(1,25); (*(M2[361]))[380] = M1(1,26); (*(M2[361]))[386] = M1(1,27); (*(M2[362]))[288] = M1(2,2); (*(M2[362]))[292] = M1(2,4); (*(M2[362]))[293] = M1(2,5); (*(M2[362]))[294] = M1(2,6); (*(M2[362]))[297] = M1(2,7); (*(M2[362]))[298] = M1(2,8); (*(M2[362]))[301] = M1(2,9); (*(M2[362]))[307] = M1(2,10); (*(M2[362]))[308] = M1(2,11); (*(M2[362]))[309] = M1(2,12); (*(M2[362]))[312] = M1(2,13); (*(M2[362]))[313] = M1(2,14); (*(M2[362]))[316] = M1(2,15); (*(M2[362]))[322] = M1(2,16); (*(M2[362]))[323] = M1(2,17); (*(M2[362]))[326] = M1(2,18); (*(M2[362]))[332] = M1(2,19); (*(M2[362]))[376] = M1(2,24); (*(M2[362]))[377] = M1(2,25); (*(M2[362]))[380] = M1(2,26); (*(M2[362]))[386] = M1(2,27); (*(M2[363]))[289] = M1(3,3); (*(M2[363]))[292] = M1(3,4); (*(M2[363]))[293] = M1(3,5); (*(M2[363]))[294] = M1(3,6); (*(M2[363]))[297] = M1(3,7); (*(M2[363]))[298] = M1(3,8); (*(M2[363]))[301] = M1(3,9); (*(M2[363]))[307] = M1(3,10); (*(M2[363]))[308] = M1(3,11); (*(M2[363]))[309] = M1(3,12); (*(M2[363]))[312] = M1(3,13); (*(M2[363]))[313] = M1(3,14); (*(M2[363]))[316] = M1(3,15); (*(M2[363]))[322] = M1(3,16); (*(M2[363]))[323] = M1(3,17); (*(M2[363]))[326] = M1(3,18); (*(M2[363]))[332] = M1(3,19); (*(M2[363]))[376] = M1(3,24); (*(M2[363]))[377] = M1(3,25); (*(M2[363]))[380] = M1(3,26); (*(M2[363]))[386] = M1(3,27); (*(M2[364]))[342] = M1(4,20); (*(M2[364]))[344] = M1(4,21); (*(M2[364]))[351] = M1(4,22); (*(M2[364]))[367] = M1(4,23); (*(M2[364]))[392] = M1(4,28); (*(M2[365]))[285] = M1(0,0); (*(M2[365]))[291] = M1(0,4); (*(M2[365]))[292] = M1(0,5); (*(M2[365]))[293] = M1(0,6); (*(M2[365]))[296] = M1(0,7); (*(M2[365]))[297] = M1(0,8); (*(M2[365]))[300] = M1(0,9); (*(M2[365]))[306] = M1(0,10); (*(M2[365]))[307] = M1(0,11); (*(M2[365]))[308] = M1(0,12); (*(M2[365]))[311] = M1(0,13); (*(M2[365]))[312] = M1(0,14); (*(M2[365]))[315] = M1(0,15); (*(M2[365]))[321] = M1(0,16); (*(M2[365]))[322] = M1(0,17); (*(M2[365]))[325] = M1(0,18); (*(M2[365]))[331] = M1(0,19); (*(M2[365]))[375] = M1(0,24); (*(M2[365]))[376] = M1(0,25); (*(M2[365]))[379] = M1(0,26); (*(M2[365]))[385] = M1(0,27); (*(M2[366]))[286] = M1(1,1); (*(M2[366]))[291] = M1(1,4); (*(M2[366]))[292] = M1(1,5); (*(M2[366]))[293] = M1(1,6); (*(M2[366]))[296] = M1(1,7); (*(M2[366]))[297] = M1(1,8); (*(M2[366]))[300] = M1(1,9); (*(M2[366]))[306] = M1(1,10); (*(M2[366]))[307] = M1(1,11); (*(M2[366]))[308] = M1(1,12); (*(M2[366]))[311] = M1(1,13); (*(M2[366]))[312] = M1(1,14); (*(M2[366]))[315] = M1(1,15); (*(M2[366]))[321] = M1(1,16); (*(M2[366]))[322] = M1(1,17); (*(M2[366]))[325] = M1(1,18); (*(M2[366]))[331] = M1(1,19); (*(M2[366]))[375] = M1(1,24); (*(M2[366]))[376] = M1(1,25); (*(M2[366]))[379] = M1(1,26); (*(M2[366]))[385] = M1(1,27); (*(M2[367]))[287] = M1(2,2); (*(M2[367]))[291] = M1(2,4); (*(M2[367]))[292] = M1(2,5); (*(M2[367]))[293] = M1(2,6); (*(M2[367]))[296] = M1(2,7); (*(M2[367]))[297] = M1(2,8); (*(M2[367]))[300] = M1(2,9); (*(M2[367]))[306] = M1(2,10); (*(M2[367]))[307] = M1(2,11); (*(M2[367]))[308] = M1(2,12); (*(M2[367]))[311] = M1(2,13); (*(M2[367]))[312] = M1(2,14); (*(M2[367]))[315] = M1(2,15); (*(M2[367]))[321] = M1(2,16); (*(M2[367]))[322] = M1(2,17); (*(M2[367]))[325] = M1(2,18); (*(M2[367]))[331] = M1(2,19); (*(M2[367]))[375] = M1(2,24); (*(M2[367]))[376] = M1(2,25); (*(M2[367]))[379] = M1(2,26); (*(M2[367]))[385] = M1(2,27); (*(M2[368]))[288] = M1(3,3); (*(M2[368]))[291] = M1(3,4); (*(M2[368]))[292] = M1(3,5); (*(M2[368]))[293] = M1(3,6); (*(M2[368]))[296] = M1(3,7); (*(M2[368]))[297] = M1(3,8); (*(M2[368]))[300] = M1(3,9); (*(M2[368]))[306] = M1(3,10); (*(M2[368]))[307] = M1(3,11); (*(M2[368]))[308] = M1(3,12); (*(M2[368]))[311] = M1(3,13); (*(M2[368]))[312] = M1(3,14); (*(M2[368]))[315] = M1(3,15); (*(M2[368]))[321] = M1(3,16); (*(M2[368]))[322] = M1(3,17); (*(M2[368]))[325] = M1(3,18); (*(M2[368]))[331] = M1(3,19); (*(M2[368]))[375] = M1(3,24); (*(M2[368]))[376] = M1(3,25); (*(M2[368]))[379] = M1(3,26); (*(M2[368]))[385] = M1(3,27); (*(M2[369]))[341] = M1(4,20); (*(M2[369]))[343] = M1(4,21); (*(M2[369]))[350] = M1(4,22); (*(M2[369]))[366] = M1(4,23); (*(M2[369]))[391] = M1(4,28); (*(M2[370]))[356] = M1(0,0); (*(M2[370]))[360] = M1(0,4); (*(M2[370]))[361] = M1(0,5); (*(M2[370]))[362] = M1(0,6); (*(M2[370]))[363] = M1(0,7); (*(M2[370]))[364] = M1(0,8); (*(M2[370]))[365] = M1(0,9); (*(M2[370]))[366] = M1(0,10); (*(M2[370]))[367] = M1(0,11); (*(M2[370]))[368] = M1(0,12); (*(M2[370]))[369] = M1(0,13); (*(M2[370]))[370] = M1(0,14); (*(M2[370]))[371] = M1(0,15); (*(M2[370]))[372] = M1(0,16); (*(M2[370]))[373] = M1(0,17); (*(M2[370]))[374] = M1(0,18); (*(M2[370]))[396] = M1(0,19); (*(M2[370]))[403] = M1(0,24); (*(M2[370]))[404] = M1(0,25); (*(M2[370]))[405] = M1(0,26); (*(M2[370]))[406] = M1(0,27); (*(M2[371]))[357] = M1(1,1); (*(M2[371]))[360] = M1(1,4); (*(M2[371]))[361] = M1(1,5); (*(M2[371]))[362] = M1(1,6); (*(M2[371]))[363] = M1(1,7); (*(M2[371]))[364] = M1(1,8); (*(M2[371]))[365] = M1(1,9); (*(M2[371]))[366] = M1(1,10); (*(M2[371]))[367] = M1(1,11); (*(M2[371]))[368] = M1(1,12); (*(M2[371]))[369] = M1(1,13); (*(M2[371]))[370] = M1(1,14); (*(M2[371]))[371] = M1(1,15); (*(M2[371]))[372] = M1(1,16); (*(M2[371]))[373] = M1(1,17); (*(M2[371]))[374] = M1(1,18); (*(M2[371]))[396] = M1(1,19); (*(M2[371]))[403] = M1(1,24); (*(M2[371]))[404] = M1(1,25); (*(M2[371]))[405] = M1(1,26); (*(M2[371]))[406] = M1(1,27); (*(M2[372]))[358] = M1(2,2); (*(M2[372]))[360] = M1(2,4); (*(M2[372]))[361] = M1(2,5); (*(M2[372]))[362] = M1(2,6); (*(M2[372]))[363] = M1(2,7); (*(M2[372]))[364] = M1(2,8); (*(M2[372]))[365] = M1(2,9); (*(M2[372]))[366] = M1(2,10); (*(M2[372]))[367] = M1(2,11); (*(M2[372]))[368] = M1(2,12); (*(M2[372]))[369] = M1(2,13); (*(M2[372]))[370] = M1(2,14); (*(M2[372]))[371] = M1(2,15); (*(M2[372]))[372] = M1(2,16); (*(M2[372]))[373] = M1(2,17); (*(M2[372]))[374] = M1(2,18); (*(M2[372]))[396] = M1(2,19); (*(M2[372]))[403] = M1(2,24); (*(M2[372]))[404] = M1(2,25); (*(M2[372]))[405] = M1(2,26); (*(M2[372]))[406] = M1(2,27); (*(M2[373]))[359] = M1(3,3); (*(M2[373]))[360] = M1(3,4); (*(M2[373]))[361] = M1(3,5); (*(M2[373]))[362] = M1(3,6); (*(M2[373]))[363] = M1(3,7); (*(M2[373]))[364] = M1(3,8); (*(M2[373]))[365] = M1(3,9); (*(M2[373]))[366] = M1(3,10); (*(M2[373]))[367] = M1(3,11); (*(M2[373]))[368] = M1(3,12); (*(M2[373]))[369] = M1(3,13); (*(M2[373]))[370] = M1(3,14); (*(M2[373]))[371] = M1(3,15); (*(M2[373]))[372] = M1(3,16); (*(M2[373]))[373] = M1(3,17); (*(M2[373]))[374] = M1(3,18); (*(M2[373]))[396] = M1(3,19); (*(M2[373]))[403] = M1(3,24); (*(M2[373]))[404] = M1(3,25); (*(M2[373]))[405] = M1(3,26); (*(M2[373]))[406] = M1(3,27); (*(M2[374]))[385] = M1(4,20); (*(M2[374]))[387] = M1(4,21); (*(M2[374]))[390] = M1(4,22); (*(M2[374]))[400] = M1(4,23); (*(M2[374]))[410] = M1(4,28); (*(M2[375]))[346] = M1(0,0); (*(M2[375]))[350] = M1(0,4); (*(M2[375]))[351] = M1(0,5); (*(M2[375]))[352] = M1(0,6); (*(M2[375]))[353] = M1(0,7); (*(M2[375]))[354] = M1(0,8); (*(M2[375]))[355] = M1(0,9); (*(M2[375]))[360] = M1(0,10); (*(M2[375]))[361] = M1(0,11); (*(M2[375]))[362] = M1(0,12); (*(M2[375]))[363] = M1(0,13); (*(M2[375]))[364] = M1(0,14); (*(M2[375]))[365] = M1(0,15); (*(M2[375]))[369] = M1(0,16); (*(M2[375]))[370] = M1(0,17); (*(M2[375]))[371] = M1(0,18); (*(M2[375]))[374] = M1(0,19); (*(M2[375]))[394] = M1(0,24); (*(M2[375]))[401] = M1(0,25); (*(M2[375]))[402] = M1(0,26); (*(M2[375]))[405] = M1(0,27); (*(M2[376]))[347] = M1(1,1); (*(M2[376]))[350] = M1(1,4); (*(M2[376]))[351] = M1(1,5); (*(M2[376]))[352] = M1(1,6); (*(M2[376]))[353] = M1(1,7); (*(M2[376]))[354] = M1(1,8); (*(M2[376]))[355] = M1(1,9); (*(M2[376]))[360] = M1(1,10); (*(M2[376]))[361] = M1(1,11); (*(M2[376]))[362] = M1(1,12); (*(M2[376]))[363] = M1(1,13); (*(M2[376]))[364] = M1(1,14); (*(M2[376]))[365] = M1(1,15); (*(M2[376]))[369] = M1(1,16); (*(M2[376]))[370] = M1(1,17); (*(M2[376]))[371] = M1(1,18); (*(M2[376]))[374] = M1(1,19); (*(M2[376]))[394] = M1(1,24); (*(M2[376]))[401] = M1(1,25); (*(M2[376]))[402] = M1(1,26); (*(M2[376]))[405] = M1(1,27); (*(M2[377]))[348] = M1(2,2); (*(M2[377]))[350] = M1(2,4); (*(M2[377]))[351] = M1(2,5); (*(M2[377]))[352] = M1(2,6); (*(M2[377]))[353] = M1(2,7); (*(M2[377]))[354] = M1(2,8); (*(M2[377]))[355] = M1(2,9); (*(M2[377]))[360] = M1(2,10); (*(M2[377]))[361] = M1(2,11); (*(M2[377]))[362] = M1(2,12); (*(M2[377]))[363] = M1(2,13); (*(M2[377]))[364] = M1(2,14); (*(M2[377]))[365] = M1(2,15); (*(M2[377]))[369] = M1(2,16); (*(M2[377]))[370] = M1(2,17); (*(M2[377]))[371] = M1(2,18); (*(M2[377]))[374] = M1(2,19); (*(M2[377]))[394] = M1(2,24); (*(M2[377]))[401] = M1(2,25); (*(M2[377]))[402] = M1(2,26); (*(M2[377]))[405] = M1(2,27); (*(M2[378]))[349] = M1(3,3); (*(M2[378]))[350] = M1(3,4); (*(M2[378]))[351] = M1(3,5); (*(M2[378]))[352] = M1(3,6); (*(M2[378]))[353] = M1(3,7); (*(M2[378]))[354] = M1(3,8); (*(M2[378]))[355] = M1(3,9); (*(M2[378]))[360] = M1(3,10); (*(M2[378]))[361] = M1(3,11); (*(M2[378]))[362] = M1(3,12); (*(M2[378]))[363] = M1(3,13); (*(M2[378]))[364] = M1(3,14); (*(M2[378]))[365] = M1(3,15); (*(M2[378]))[369] = M1(3,16); (*(M2[378]))[370] = M1(3,17); (*(M2[378]))[371] = M1(3,18); (*(M2[378]))[374] = M1(3,19); (*(M2[378]))[394] = M1(3,24); (*(M2[378]))[401] = M1(3,25); (*(M2[378]))[402] = M1(3,26); (*(M2[378]))[405] = M1(3,27); (*(M2[379]))[379] = M1(4,20); (*(M2[379]))[381] = M1(4,21); (*(M2[379]))[384] = M1(4,22); (*(M2[379]))[399] = M1(4,23); (*(M2[379]))[409] = M1(4,28); (*(M2[380]))[342] = M1(0,0); (*(M2[380]))[347] = M1(0,4); (*(M2[380]))[348] = M1(0,5); (*(M2[380]))[349] = M1(0,6); (*(M2[380]))[351] = M1(0,7); (*(M2[380]))[352] = M1(0,8); (*(M2[380]))[354] = M1(0,9); (*(M2[380]))[357] = M1(0,10); (*(M2[380]))[358] = M1(0,11); (*(M2[380]))[359] = M1(0,12); (*(M2[380]))[361] = M1(0,13); (*(M2[380]))[362] = M1(0,14); (*(M2[380]))[364] = M1(0,15); (*(M2[380]))[367] = M1(0,16); (*(M2[380]))[368] = M1(0,17); (*(M2[380]))[370] = M1(0,18); (*(M2[380]))[373] = M1(0,19); (*(M2[380]))[392] = M1(0,24); (*(M2[380]))[393] = M1(0,25); (*(M2[380]))[401] = M1(0,26); (*(M2[380]))[404] = M1(0,27); (*(M2[381]))[343] = M1(1,1); (*(M2[381]))[347] = M1(1,4); (*(M2[381]))[348] = M1(1,5); (*(M2[381]))[349] = M1(1,6); (*(M2[381]))[351] = M1(1,7); (*(M2[381]))[352] = M1(1,8); (*(M2[381]))[354] = M1(1,9); (*(M2[381]))[357] = M1(1,10); (*(M2[381]))[358] = M1(1,11); (*(M2[381]))[359] = M1(1,12); (*(M2[381]))[361] = M1(1,13); (*(M2[381]))[362] = M1(1,14); (*(M2[381]))[364] = M1(1,15); (*(M2[381]))[367] = M1(1,16); (*(M2[381]))[368] = M1(1,17); (*(M2[381]))[370] = M1(1,18); (*(M2[381]))[373] = M1(1,19); (*(M2[381]))[392] = M1(1,24); (*(M2[381]))[393] = M1(1,25); (*(M2[381]))[401] = M1(1,26); (*(M2[381]))[404] = M1(1,27); (*(M2[382]))[344] = M1(2,2); (*(M2[382]))[347] = M1(2,4); (*(M2[382]))[348] = M1(2,5); (*(M2[382]))[349] = M1(2,6); (*(M2[382]))[351] = M1(2,7); (*(M2[382]))[352] = M1(2,8); (*(M2[382]))[354] = M1(2,9); (*(M2[382]))[357] = M1(2,10); (*(M2[382]))[358] = M1(2,11); (*(M2[382]))[359] = M1(2,12); (*(M2[382]))[361] = M1(2,13); (*(M2[382]))[362] = M1(2,14); (*(M2[382]))[364] = M1(2,15); (*(M2[382]))[367] = M1(2,16); (*(M2[382]))[368] = M1(2,17); (*(M2[382]))[370] = M1(2,18); (*(M2[382]))[373] = M1(2,19); (*(M2[382]))[392] = M1(2,24); (*(M2[382]))[393] = M1(2,25); (*(M2[382]))[401] = M1(2,26); (*(M2[382]))[404] = M1(2,27); (*(M2[383]))[345] = M1(3,3); (*(M2[383]))[347] = M1(3,4); (*(M2[383]))[348] = M1(3,5); (*(M2[383]))[349] = M1(3,6); (*(M2[383]))[351] = M1(3,7); (*(M2[383]))[352] = M1(3,8); (*(M2[383]))[354] = M1(3,9); (*(M2[383]))[357] = M1(3,10); (*(M2[383]))[358] = M1(3,11); (*(M2[383]))[359] = M1(3,12); (*(M2[383]))[361] = M1(3,13); (*(M2[383]))[362] = M1(3,14); (*(M2[383]))[364] = M1(3,15); (*(M2[383]))[367] = M1(3,16); (*(M2[383]))[368] = M1(3,17); (*(M2[383]))[370] = M1(3,18); (*(M2[383]))[373] = M1(3,19); (*(M2[383]))[392] = M1(3,24); (*(M2[383]))[393] = M1(3,25); (*(M2[383]))[401] = M1(3,26); (*(M2[383]))[404] = M1(3,27); (*(M2[384]))[376] = M1(4,20); (*(M2[384]))[378] = M1(4,21); (*(M2[384]))[383] = M1(4,22); (*(M2[384]))[398] = M1(4,23); (*(M2[384]))[408] = M1(4,28); (*(M2[385]))[341] = M1(0,0); (*(M2[385]))[346] = M1(0,4); (*(M2[385]))[347] = M1(0,5); (*(M2[385]))[348] = M1(0,6); (*(M2[385]))[350] = M1(0,7); (*(M2[385]))[351] = M1(0,8); (*(M2[385]))[353] = M1(0,9); (*(M2[385]))[356] = M1(0,10); (*(M2[385]))[357] = M1(0,11); (*(M2[385]))[358] = M1(0,12); (*(M2[385]))[360] = M1(0,13); (*(M2[385]))[361] = M1(0,14); (*(M2[385]))[363] = M1(0,15); (*(M2[385]))[366] = M1(0,16); (*(M2[385]))[367] = M1(0,17); (*(M2[385]))[369] = M1(0,18); (*(M2[385]))[372] = M1(0,19); (*(M2[385]))[391] = M1(0,24); (*(M2[385]))[392] = M1(0,25); (*(M2[385]))[394] = M1(0,26); (*(M2[385]))[403] = M1(0,27); (*(M2[386]))[342] = M1(1,1); (*(M2[386]))[346] = M1(1,4); (*(M2[386]))[347] = M1(1,5); (*(M2[386]))[348] = M1(1,6); (*(M2[386]))[350] = M1(1,7); (*(M2[386]))[351] = M1(1,8); (*(M2[386]))[353] = M1(1,9); (*(M2[386]))[356] = M1(1,10); (*(M2[386]))[357] = M1(1,11); (*(M2[386]))[358] = M1(1,12); (*(M2[386]))[360] = M1(1,13); (*(M2[386]))[361] = M1(1,14); (*(M2[386]))[363] = M1(1,15); (*(M2[386]))[366] = M1(1,16); (*(M2[386]))[367] = M1(1,17); (*(M2[386]))[369] = M1(1,18); (*(M2[386]))[372] = M1(1,19); (*(M2[386]))[391] = M1(1,24); (*(M2[386]))[392] = M1(1,25); (*(M2[386]))[394] = M1(1,26); (*(M2[386]))[403] = M1(1,27); (*(M2[387]))[343] = M1(2,2); (*(M2[387]))[346] = M1(2,4); (*(M2[387]))[347] = M1(2,5); (*(M2[387]))[348] = M1(2,6); (*(M2[387]))[350] = M1(2,7); (*(M2[387]))[351] = M1(2,8); (*(M2[387]))[353] = M1(2,9); (*(M2[387]))[356] = M1(2,10); (*(M2[387]))[357] = M1(2,11); (*(M2[387]))[358] = M1(2,12); (*(M2[387]))[360] = M1(2,13); (*(M2[387]))[361] = M1(2,14); (*(M2[387]))[363] = M1(2,15); (*(M2[387]))[366] = M1(2,16); (*(M2[387]))[367] = M1(2,17); (*(M2[387]))[369] = M1(2,18); (*(M2[387]))[372] = M1(2,19); (*(M2[387]))[391] = M1(2,24); (*(M2[387]))[392] = M1(2,25); (*(M2[387]))[394] = M1(2,26); (*(M2[387]))[403] = M1(2,27); (*(M2[388]))[344] = M1(3,3); (*(M2[388]))[346] = M1(3,4); (*(M2[388]))[347] = M1(3,5); (*(M2[388]))[348] = M1(3,6); (*(M2[388]))[350] = M1(3,7); (*(M2[388]))[351] = M1(3,8); (*(M2[388]))[353] = M1(3,9); (*(M2[388]))[356] = M1(3,10); (*(M2[388]))[357] = M1(3,11); (*(M2[388]))[358] = M1(3,12); (*(M2[388]))[360] = M1(3,13); (*(M2[388]))[361] = M1(3,14); (*(M2[388]))[363] = M1(3,15); (*(M2[388]))[366] = M1(3,16); (*(M2[388]))[367] = M1(3,17); (*(M2[388]))[369] = M1(3,18); (*(M2[388]))[372] = M1(3,19); (*(M2[388]))[391] = M1(3,24); (*(M2[388]))[392] = M1(3,25); (*(M2[388]))[394] = M1(3,26); (*(M2[388]))[403] = M1(3,27); (*(M2[389]))[375] = M1(4,20); (*(M2[389]))[377] = M1(4,21); (*(M2[389]))[382] = M1(4,22); (*(M2[389]))[397] = M1(4,23); (*(M2[389]))[407] = M1(4,28); (*(M2[390]))[375] = M1(0,0); (*(M2[390]))[379] = M1(0,4); (*(M2[390]))[380] = M1(0,5); (*(M2[390]))[381] = M1(0,6); (*(M2[390]))[382] = M1(0,7); (*(M2[390]))[383] = M1(0,8); (*(M2[390]))[384] = M1(0,9); (*(M2[390]))[385] = M1(0,10); (*(M2[390]))[386] = M1(0,11); (*(M2[390]))[387] = M1(0,12); (*(M2[390]))[388] = M1(0,13); (*(M2[390]))[389] = M1(0,14); (*(M2[390]))[390] = M1(0,15); (*(M2[390]))[397] = M1(0,16); (*(M2[390]))[398] = M1(0,17); (*(M2[390]))[399] = M1(0,18); (*(M2[390]))[400] = M1(0,19); (*(M2[390]))[407] = M1(0,24); (*(M2[390]))[408] = M1(0,25); (*(M2[390]))[409] = M1(0,26); (*(M2[390]))[410] = M1(0,27); (*(M2[391]))[376] = M1(1,1); (*(M2[391]))[379] = M1(1,4); (*(M2[391]))[380] = M1(1,5); (*(M2[391]))[381] = M1(1,6); (*(M2[391]))[382] = M1(1,7); (*(M2[391]))[383] = M1(1,8); (*(M2[391]))[384] = M1(1,9); (*(M2[391]))[385] = M1(1,10); (*(M2[391]))[386] = M1(1,11); (*(M2[391]))[387] = M1(1,12); (*(M2[391]))[388] = M1(1,13); (*(M2[391]))[389] = M1(1,14); (*(M2[391]))[390] = M1(1,15); (*(M2[391]))[397] = M1(1,16); (*(M2[391]))[398] = M1(1,17); (*(M2[391]))[399] = M1(1,18); (*(M2[391]))[400] = M1(1,19); (*(M2[391]))[407] = M1(1,24); (*(M2[391]))[408] = M1(1,25); (*(M2[391]))[409] = M1(1,26); (*(M2[391]))[410] = M1(1,27); (*(M2[392]))[377] = M1(2,2); (*(M2[392]))[379] = M1(2,4); (*(M2[392]))[380] = M1(2,5); (*(M2[392]))[381] = M1(2,6); (*(M2[392]))[382] = M1(2,7); (*(M2[392]))[383] = M1(2,8); (*(M2[392]))[384] = M1(2,9); (*(M2[392]))[385] = M1(2,10); (*(M2[392]))[386] = M1(2,11); (*(M2[392]))[387] = M1(2,12); (*(M2[392]))[388] = M1(2,13); (*(M2[392]))[389] = M1(2,14); (*(M2[392]))[390] = M1(2,15); (*(M2[392]))[397] = M1(2,16); (*(M2[392]))[398] = M1(2,17); (*(M2[392]))[399] = M1(2,18); (*(M2[392]))[400] = M1(2,19); (*(M2[392]))[407] = M1(2,24); (*(M2[392]))[408] = M1(2,25); (*(M2[392]))[409] = M1(2,26); (*(M2[392]))[410] = M1(2,27); (*(M2[393]))[378] = M1(3,3); (*(M2[393]))[379] = M1(3,4); (*(M2[393]))[380] = M1(3,5); (*(M2[393]))[381] = M1(3,6); (*(M2[393]))[382] = M1(3,7); (*(M2[393]))[383] = M1(3,8); (*(M2[393]))[384] = M1(3,9); (*(M2[393]))[385] = M1(3,10); (*(M2[393]))[386] = M1(3,11); (*(M2[393]))[387] = M1(3,12); (*(M2[393]))[388] = M1(3,13); (*(M2[393]))[389] = M1(3,14); (*(M2[393]))[390] = M1(3,15); (*(M2[393]))[397] = M1(3,16); (*(M2[393]))[398] = M1(3,17); (*(M2[393]))[399] = M1(3,18); (*(M2[393]))[400] = M1(3,19); (*(M2[393]))[407] = M1(3,24); (*(M2[393]))[408] = M1(3,25); (*(M2[393]))[409] = M1(3,26); (*(M2[393]))[410] = M1(3,27); (*(M2[394]))[391] = M1(4,20); (*(M2[394]))[393] = M1(4,21); (*(M2[394]))[402] = M1(4,22); (*(M2[394]))[406] = M1(4,23); (*(M2[394]))[411] = M1(4,28); opengv::math::gauss_jordan(M2,340); Action = Eigen::Matrix::Zero(); for( int s = 0; s < 16; s++ ) Action(0,s) -= (*(M2[340]))[396+s]; for( int s = 0; s < 16; s++ ) Action(1,s) -= (*(M2[372]))[396+s]; for( int s = 0; s < 16; s++ ) Action(2,s) -= (*(M2[373]))[396+s]; for( int s = 0; s < 16; s++ ) Action(3,s) -= (*(M2[374]))[396+s]; Action(4,0) = 1.0; for( int s = 0; s < 16; s++ ) Action(5,s) -= (*(M2[389]))[396+s]; for( int s = 0; s < 16; s++ ) Action(6,s) -= (*(M2[390]))[396+s]; Action(7,1) = 1.0; Action(8,2) = 1.0; Action(9,3) = 1.0; Action(10,4) = 1.0; Action(11,7) = 1.0; Action(12,8) = 1.0; Action(13,9) = 1.0; Action(14,10) = 1.0; Action(15,14) = 1.0; //columns of Action mean: // x_4^4 x_1*x_4^2 x_2*x_4^2 x_3*x_4^2 x_4^3 x_2*x_3 x_3^2 x_1*x_4 x_2*x_4 x_3*x_4 x_4^2 x_1 x_2 x_3 x_4 1 for( int r = 0; r < 395; r++ ) delete M2[r]; } opengv/src/absolute_pose/NoncentralAbsoluteAdapter.cpp0000664016516101651610000001170713344612246022257 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::absolute_pose::NoncentralAbsoluteAdapter::NoncentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const camCorrespondences_t & camCorrespondences, const points_t & points, const translations_t & camOffsets, const rotations_t & camRotations ) : AbsoluteAdapterBase(), _bearingVectors(bearingVectors), _camCorrespondences(camCorrespondences), _points(points), _camOffsets(camOffsets), _camRotations(camRotations) {} opengv::absolute_pose::NoncentralAbsoluteAdapter::NoncentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const camCorrespondences_t & camCorrespondences, const points_t & points, const translations_t & camOffsets, const rotations_t & camRotations, const rotation_t & R ) : AbsoluteAdapterBase(R), _bearingVectors(bearingVectors), _camCorrespondences(camCorrespondences), _points(points), _camOffsets(camOffsets), _camRotations(camRotations) {} opengv::absolute_pose::NoncentralAbsoluteAdapter::NoncentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const camCorrespondences_t & camCorrespondences, const points_t & points, const translations_t & camOffsets, const rotations_t & camRotations, const translation_t & t, const rotation_t & R ) : AbsoluteAdapterBase(t,R), _bearingVectors(bearingVectors), _camCorrespondences(camCorrespondences), _points(points), _camOffsets(camOffsets), _camRotations(camRotations) {} opengv::absolute_pose::NoncentralAbsoluteAdapter::~NoncentralAbsoluteAdapter() {} opengv::bearingVector_t opengv::absolute_pose::NoncentralAbsoluteAdapter:: getBearingVector( size_t index ) const { assert(index < _bearingVectors.size()); return _bearingVectors[index]; } double opengv::absolute_pose::NoncentralAbsoluteAdapter:: getWeight( size_t index ) const { return 1.0; } opengv::point_t opengv::absolute_pose::NoncentralAbsoluteAdapter:: getPoint( size_t index ) const { assert(index < _bearingVectors.size()); return _points[index]; } opengv::translation_t opengv::absolute_pose::NoncentralAbsoluteAdapter:: getCamOffset( size_t index ) const { assert(_camCorrespondences[index] < _camOffsets.size()); return _camOffsets[_camCorrespondences[index]]; } opengv::rotation_t opengv::absolute_pose::NoncentralAbsoluteAdapter:: getCamRotation( size_t index ) const { assert(_camCorrespondences[index] < _camRotations.size()); return _camRotations[_camCorrespondences[index]]; } size_t opengv::absolute_pose::NoncentralAbsoluteAdapter:: getNumberCorrespondences() const { return _bearingVectors.size(); } opengv/src/absolute_pose/methods.cpp0000664016516101651610000006104213344612246016614 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include #include #include #include #include #include opengv::translation_t opengv::absolute_pose::p2p( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { assert(indices.size()>1); return p2p( adapter, indices[0], indices[1] ); } opengv::translation_t opengv::absolute_pose::p2p( const AbsoluteAdapterBase & adapter, size_t index0, size_t index1) { Eigen::Vector3d e1 = adapter.getBearingVector(index0); Eigen::Vector3d e3 = adapter.getBearingVector(index1); e3 = e1.cross(e3); e3 = e3/e3.norm(); Eigen::Vector3d e2 = e3.cross(e1); rotation_t T; T.row(0) = e1.transpose(); T.row(1) = e2.transpose(); T.row(2) = e3.transpose(); Eigen::Vector3d n1 = adapter.getPoint(index1) - adapter.getPoint(index0); n1 = n1/n1.norm(); Eigen::Vector3d n3; if( (fabs(n1[0]) > fabs(n1[1])) && (fabs(n1[0]) > fabs(n1[2])) ) { n3[1] = 1.0; n3[2] = 0.0; n3[0] = -n1[1]/n1[0]; } else { if( (fabs(n1[1]) > fabs(n1[0])) && (fabs(n1[1]) > fabs(n1[2])) ) { n3[2] = 1.0; n3[0] = 0.0; n3[1] = -n1[2]/n1[1]; } else { n3[0] = 1.0; n3[1] = 0.0; n3[2] = -n1[0]/n1[2]; } } n3 = n3 / n3.norm(); Eigen::Vector3d n2 = n3.cross(n1); rotation_t N; N.row(0) = n1.transpose(); N.row(1) = n2.transpose(); N.row(2) = n3.transpose(); Eigen::Matrix3d Q = T * adapter.getR().transpose() * N.transpose(); Eigen::Vector3d temp1 = adapter.getPoint(index1) - adapter.getPoint(index0); double d_12 = temp1.norm(); Eigen::Vector3d temp2 = adapter.getBearingVector(index1); double cos_beta = e1.dot(temp2); double b = 1/( 1 - pow( cos_beta, 2 ) ) - 1; if( cos_beta < 0 ) b = -sqrt(b); else b = sqrt(b); double temp3 = d_12 * ( Q(1,0) * b - Q(0,0) ); translation_t solution = -temp3 * Q.row(0).transpose(); solution = adapter.getPoint(index0) + N.transpose()*solution; if( solution(0,0) != solution(0,0) || solution(1,0) != solution(1,0) || solution(2,0) != solution(2,0) ) solution = Eigen::Vector3d::Zero(); return solution; } opengv::transformations_t opengv::absolute_pose::p3p_kneip( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { assert(indices.size()>2); return p3p_kneip( adapter, indices[0], indices[1], indices[2] ); } opengv::transformations_t opengv::absolute_pose::p3p_kneip( const AbsoluteAdapterBase & adapter, size_t index0, size_t index1, size_t index2) { bearingVectors_t f; f.push_back(adapter.getBearingVector(index0)); f.push_back(adapter.getBearingVector(index1)); f.push_back(adapter.getBearingVector(index2)); points_t p; p.push_back(adapter.getPoint(index0)); p.push_back(adapter.getPoint(index1)); p.push_back(adapter.getPoint(index2)); transformations_t solutions; modules::p3p_kneip_main( f, p, solutions ); return solutions; } opengv::transformations_t opengv::absolute_pose::p3p_gao( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { assert(indices.size()>2); return p3p_gao( adapter, indices[0], indices[1], indices[2] ); } opengv::transformations_t opengv::absolute_pose::p3p_gao( const AbsoluteAdapterBase & adapter, size_t index0, size_t index1, size_t index2) { bearingVectors_t f; f.push_back(adapter.getBearingVector(index0)); f.push_back(adapter.getBearingVector(index1)); f.push_back(adapter.getBearingVector(index2)); points_t p; p.push_back(adapter.getPoint(index0)); p.push_back(adapter.getPoint(index1)); p.push_back(adapter.getPoint(index2)); transformations_t solutions; modules::p3p_gao_main( f, p, solutions ); return solutions; } opengv::transformations_t opengv::absolute_pose::gp3p( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { assert(indices.size()>2); Eigen::Matrix3d f; Eigen::Matrix3d v; Eigen::Matrix3d p; for(size_t i = 0; i < 3; i++) { f.col(i) = adapter.getBearingVector(indices[i]); rotation_t R = adapter.getCamRotation(indices[i]); //unrotate the bearingVectors already so the camera rotation doesn't appear //in the problem f.col(i) = R * f.col(i); v.col(i) = adapter.getCamOffset(indices[i]); p.col(i) = adapter.getPoint(indices[i]); } transformations_t solutions; modules::gp3p_main(f,v,p,solutions); return solutions; } opengv::transformations_t opengv::absolute_pose::gp3p( const AbsoluteAdapterBase & adapter, size_t index0, size_t index1, size_t index2) { std::vector indices; indices.push_back(index0); indices.push_back(index1); indices.push_back(index2); return gp3p(adapter,indices); } namespace opengv { namespace absolute_pose { transformation_t epnp( const AbsoluteAdapterBase & adapter, const Indices & indices ) { //starting from 4 points, we have a unique solution assert(indices.size() > 5); modules::Epnp PnP; PnP.set_maximum_number_of_correspondences(indices.size()); PnP.reset_correspondences(); for( size_t i = 0; i < indices.size(); i++ ) { point_t p = adapter.getPoint(indices[i]); bearingVector_t f = adapter.getBearingVector(indices[i]); PnP.add_correspondence(p[0], p[1], p[2], f[0], f[1], f[2]); } double R_epnp[3][3], t_epnp[3]; PnP.compute_pose(R_epnp, t_epnp); rotation_t rotation; translation_t translation; for(int r = 0; r < 3; r++) { for(int c = 0; c < 3; c++) rotation(r,c) = R_epnp[r][c]; } translation[0] = t_epnp[0]; translation[1] = t_epnp[1]; translation[2] = t_epnp[2]; //take inverse transformation rotation.transposeInPlace(); translation = -rotation * translation; transformation_t transformation; transformation.col(3) = translation; transformation.block<3,3>(0,0) = rotation; return transformation; } } } opengv::transformation_t opengv::absolute_pose::epnp( const AbsoluteAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return epnp(adapter,idx); } opengv::transformation_t opengv::absolute_pose::epnp( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return epnp(adapter,idx); } namespace opengv { namespace absolute_pose { transformation_t gpnp( const AbsoluteAdapterBase & adapter, const Indices & indices ) { assert( indices.size() > 5 ); //compute the centroid point_t c0 = Eigen::Vector3d::Zero(); for( size_t i = 0; i < indices.size(); i++ ) c0 = c0 + adapter.getPoint(indices[i]); c0 = c0 / indices.size(); //compute the point-cloud Eigen::MatrixXd p(3,indices.size()); for( size_t i = 0; i < indices.size(); i++ ) p.col(i) = adapter.getPoint(indices[i]) - c0; //compute the moment Eigen::JacobiSVD< Eigen::MatrixXd > SVD( p, Eigen::ComputeThinU | Eigen::ComputeThinV ); //define the control points points_t c; c.push_back(c0); //c.push_back(c0 + SVD.singularValues()[0] * SVD.matrixU().col(0)); //c.push_back(c0 + SVD.singularValues()[1] * SVD.matrixU().col(1)); //c.push_back(c0 + SVD.singularValues()[2] * SVD.matrixU().col(2)); c.push_back(c0 + 15.0 * SVD.matrixU().col(0)); c.push_back(c0 + 15.0 * SVD.matrixU().col(1)); c.push_back(c0 + 15.0 * SVD.matrixU().col(2)); //derive the barycentric frame Eigen::Vector3d e1 = c[1]-c0; double e1dote1 = e1.dot(e1); Eigen::Vector3d e2 = c[2]-c0; double e2dote2 = e2.dot(e2); Eigen::Vector3d e3 = c[3]-c0; double e3dote3 = e3.dot(e3); //derive the weighting factors Eigen::MatrixXd weights(4,indices.size()); for( size_t i = 0; i < indices.size(); i++ ) { Eigen::Vector3d temp = p.col(i); weights(1,i) = temp.dot(e1)/e1dote1; weights(2,i) = temp.dot(e2)/e2dote2; weights(3,i) = temp.dot(e3)/e3dote3; weights(0,i) = 1.0-(weights(1,i)+weights(2,i)+weights(3,i)); } //setup matrix A and vector b Eigen::MatrixXd A = Eigen::MatrixXd::Zero(2*indices.size(),12); Eigen::MatrixXd b = Eigen::MatrixXd::Zero(2*indices.size(),1); for( size_t i = 0; i < indices.size(); i++ ) { translation_t camOffset = adapter.getCamOffset(indices[i]); rotation_t camRotation = adapter.getCamRotation(indices[i]); //respect the rotation bearingVector_t f = camRotation * adapter.getBearingVector(indices[i]); A(2*i,0) = weights(0,i)*f[2]; A(2*i,2) = -weights(0,i)*f[0]; A(2*i,3) = weights(1,i)*f[2]; A(2*i,5) = -weights(1,i)*f[0]; A(2*i,6) = weights(2,i)*f[2]; A(2*i,8) = -weights(2,i)*f[0]; A(2*i,9) = weights(3,i)*f[2]; A(2*i,11) = -weights(3,i)*f[0]; A(2*i+1,1) = weights(0,i)*f[2]; A(2*i+1,2) = -weights(0,i)*f[1]; A(2*i+1,4) = weights(1,i)*f[2]; A(2*i+1,5) = -weights(1,i)*f[1]; A(2*i+1,7) = weights(2,i)*f[2]; A(2*i+1,8) = -weights(2,i)*f[1]; A(2*i+1,10) = weights(3,i)*f[2]; A(2*i+1,11) = -weights(3,i)*f[1]; b(2*i,0) = f[2]*camOffset[0]-f[0]*camOffset[2]; b(2*i+1,0) = f[2]*camOffset[1]-f[1]*camOffset[2]; } //computing the SVD Eigen::JacobiSVD< Eigen::MatrixXd > SVD2( A, Eigen::ComputeThinV | Eigen::ComputeThinU ); //computing the pseudoinverse Eigen::MatrixXd invD = Eigen::MatrixXd::Zero(12,12); Eigen::MatrixXd D = SVD2.singularValues(); for( size_t i = 0; i < 12; i++ ) { if( D(i,0) > 1.e-6 ) invD(i,i) = 1.0/D(i,0); else invD(i,i) = 0.0; } //Extract the nullsapce vectors; Eigen::MatrixXd V = SVD2.matrixV(); //computing the nullspace intercept Eigen::MatrixXd pinvA = V * invD * SVD2.matrixU().transpose(); //compute the intercept Eigen::Matrix a = pinvA * b; //compute the solution transformation_t transformation; modules::gpnp_main( a, V, c, transformation ); return transformation; } } } opengv::transformation_t opengv::absolute_pose::gpnp( const AbsoluteAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return gpnp(adapter,idx); } opengv::transformation_t opengv::absolute_pose::gpnp( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return gpnp(adapter,idx); } namespace opengv { namespace absolute_pose { void fill3x10( const Eigen::Vector3d & x, Eigen::Matrix & Phi ) { double x1 = x[0]; double x2 = x[1]; double x3 = x[2]; Phi << x1, x1, -x1, -x1, 0.0, 2.0*x3, -2.0*x2, 2.0*x2, 2.0*x3, 0.0, x2, -x2, x2, -x2, -2.0*x3, 0.0, 2.0*x1, 2.0*x1, 0.0, 2.0*x3, x3, -x3, -x3, x3, 2.0*x2, -2.0*x1, 0.0, 0.0, 2.0*x1, 2.0*x2; } void f( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, Eigen::Vector3d & f ) { f[0] = (2*M(0,4)+2*C(0,4)); f[1] = (2*M(0,5)+2*C(0,5)); f[2] = (2*M(0,6)+2*C(0,6)); } void Jac( const Eigen::Matrix & M, const Eigen::Matrix & C, double gamma, Eigen::Matrix3d & Jac ) { Jac(0,0) = (2*M(4,4)+4*M(0,1)-4*M(0,0)+4*C(0,1)-4*C(0,0)); Jac(0,1) = (2*M(5,4)+2*M(0,7)+2*C(0,7)); Jac(0,2) = (2*M(6,4)+2*M(0,8)+2*C(0,8)); Jac(1,0) = (2*M(4,5)+2*M(0,7)+2*C(0,7)); Jac(1,1) = (2*M(5,5)+4*M(0,2)-4*M(0,0)+4*C(0,2)-4*C(0,0)); Jac(1,2) = (2*M(6,5)+2*M(0,9)+2*C(0,9)); Jac(2,0) = (2*M(4,6)+2*M(0,8)+2*C(0,8)); Jac(2,1) = (2*M(5,6)+2*M(0,9)+2*C(0,9)); Jac(2,2) = (2*M(6,6)+4*M(0,3)-4*M(0,0)+4*C(0,3)-4*C(0,0)); } transformations_t upnp( const AbsoluteAdapterBase & adapter, const Indices & indices ) { assert( indices.size() > 2 ); Eigen::Matrix F = Eigen::Matrix3d::Zero(); for( int i = 0; i < (int) indices.size(); i++ ) { Eigen::Matrix f = adapter.getCamRotation(indices[i]) * adapter.getBearingVector(indices[i]); F += f * f.transpose(); } Eigen::Matrix H_inv = (indices.size() * Eigen::Matrix::Identity()) - F; Eigen::Matrix H = H_inv.inverse(); Eigen::Matrix I = Eigen::Matrix::Zero(); Eigen::Matrix J = Eigen::Matrix::Zero(); Eigen::Matrix Phi; for( int i = 0; i < (int) indices.size(); i++ ) { Eigen::Matrix f = adapter.getCamRotation(indices[i]) * adapter.getBearingVector(indices[i]); Eigen::Matrix Vk = H * ( f * f.transpose() - Eigen::Matrix::Identity() ); Eigen::Matrix p = adapter.getPoint(indices[i]); Eigen::Matrix v = adapter.getCamOffset(indices[i]); fill3x10(p,Phi); I += Vk * Phi; J += Vk * v; } Eigen::Matrix M = Eigen::Matrix::Zero(); Eigen::Matrix C = Eigen::Matrix::Zero(); double gamma = 0.0; for(int i = 0; i < (int) indices.size(); i++ ) { Eigen::Matrix f = adapter.getCamRotation(indices[i]) * adapter.getBearingVector(indices[i]); Eigen::Matrix v = adapter.getCamOffset(indices[i]); Eigen::Matrix p = adapter.getPoint(indices[i]); fill3x10(p,Phi); Eigen::Matrix temp = f*f.transpose() - Eigen::Matrix::Identity(); Eigen::Matrix Ai = temp * (Phi + I); Eigen::Matrix bi = -temp * ( v + J); M += (Ai.transpose() * Ai); C += (bi.transpose() * Ai); gamma += (bi.transpose() * bi); } //now do the main computation std::vector,Eigen::aligned_allocator< std::pair > > quaternions1; if( indices.size() > 4 ) modules::upnp_main_sym( M, C, gamma, quaternions1 ); else modules::upnp_main( M, C, gamma, quaternions1 ); //prepare the output vector transformations_t transformations; //Round 1: chirality check std::vector,Eigen::aligned_allocator< std::pair > > quaternions2; for( size_t i = 0; i < quaternions1.size(); i++ ) { rotation_t Rinv = math::quaternion2rot(quaternions1[i].second); Eigen::Matrix s; modules::upnp_fill_s( quaternions1[i].second, s ); translation_t tinv = I*s - J; if( transformations.size() == 0 ) { transformation_t newTransformation; newTransformation.block<3,3>(0,0) = Rinv.transpose(); newTransformation.block<3,1>(0,3) = -newTransformation.block<3,3>(0,0) * tinv; transformations.push_back(newTransformation); } int count_negative = 0; for( int j = 0; j < (int) indices.size(); j++ ) { Eigen::Matrix f = adapter.getCamRotation(indices[j]) * adapter.getBearingVector(indices[j]); Eigen::Matrix p = adapter.getPoint(indices[j]); Eigen::Matrix v = adapter.getCamOffset(indices[j]); Eigen::Vector3d p_est = Rinv*p + tinv - v; if( p_est.transpose()*f < 0.0 ) count_negative++; } if( count_negative < floor(0.2 * indices.size() + 0.5) ) quaternions2.push_back(quaternions1[i]); } if( quaternions2.size() == 0 ) return transformations; else transformations.clear(); //Round 2: Second order optimality (plus polishing) Eigen::Matrix I_cay; Eigen::Matrix M_cay; Eigen::Matrix C_cay; double gamma_cay; for( size_t q = 0; q < quaternions2.size(); q++ ) { I_cay = Eigen::Matrix::Zero(); rotation_t Rinv = math::quaternion2rot(quaternions2[q].second); for( int i = 0; i < (int) indices.size(); i++ ) { Eigen::Matrix f = adapter.getCamRotation(indices[i]) * adapter.getBearingVector(indices[i]); Eigen::Matrix Vk = H * ( f * f.transpose() - Eigen::Matrix::Identity() ); Eigen::Matrix p = Rinv * adapter.getPoint(indices[i]); fill3x10(p,Phi); I_cay += Vk * Phi; } M_cay = Eigen::Matrix::Zero(); C_cay = Eigen::Matrix::Zero(); gamma_cay = 0.0; for(int i = 0; i < (int) indices.size(); i++ ) { Eigen::Matrix f = adapter.getCamRotation(indices[i]) * adapter.getBearingVector(indices[i]); Eigen::Matrix v = adapter.getCamOffset(indices[i]); Eigen::Matrix p = Rinv * adapter.getPoint(indices[i]); fill3x10(p,Phi); Eigen::Matrix temp = f*f.transpose() - Eigen::Matrix::Identity(); Eigen::Matrix Ai = temp * (Phi + I_cay); Eigen::Matrix bi = -temp * ( v + J); M_cay += (Ai.transpose() * Ai); C_cay += (bi.transpose() * Ai); gamma_cay += (bi.transpose() * bi); } //now analyze the eigenvalues of the "Hessian" Eigen::Vector3d val; Eigen::Matrix3d Jacobian; f( M_cay, C_cay, gamma_cay, val ); Jac( M_cay, C_cay, gamma_cay, Jacobian ); std::vector characteristicPolynomial; characteristicPolynomial.push_back(-1.0); characteristicPolynomial.push_back(Jacobian(2,2)+Jacobian(1,1)+Jacobian(0,0)); characteristicPolynomial.push_back(-Jacobian(2,2)*Jacobian(1,1)-Jacobian(2,2)*Jacobian(0,0)-Jacobian(1,1)*Jacobian(0,0)+pow(Jacobian(1,2),2)+pow(Jacobian(0,2),2)+pow(Jacobian(0,1),2)); characteristicPolynomial.push_back(Jacobian(2,2)*Jacobian(1,1)*Jacobian(0,0)+2*Jacobian(1,2)*Jacobian(0,2)*Jacobian(0,1)-Jacobian(2,2)*pow(Jacobian(0,1),2)-pow(Jacobian(1,2),2)*Jacobian(0,0)-Jacobian(1,1)*pow(Jacobian(0,2),2)); //const std::vector roots = opengv::math::o3_roots( characteristicPolynomial ); // //bool allPositive = true; //for( size_t i = 0; i < roots.size(); i++ ) //{ // if( roots[i] < 0.0 ) // { // allPositive = false; // break; // } //} // // use all results for the moment // //if( allPositive ) { //perform the polishing step Eigen::Vector3d cay = - Jacobian.inverse() * val; rotation_t Rinv2 = math::cayley2rot(cay) * Rinv; quaternion_t q = math::rot2quaternion(Rinv2); Eigen::Matrix s; modules::upnp_fill_s(q,s); translation_t tinv = I*s - J; transformation_t newTransformation; newTransformation.block<3,3>(0,0) = Rinv2.transpose(); newTransformation.block<3,1>(0,3) = -newTransformation.block<3,3>(0,0) * tinv; transformations.push_back(newTransformation); } } //if there are no results, simply add the one with lowest score if( transformations.size() == 0 ) { Eigen::Vector4d q = quaternions2[0].second; Eigen::Matrix s; modules::upnp_fill_s(q,s); translation_t tinv = I*s - J; rotation_t Rinv = math::quaternion2rot(q); transformation_t newTransformation; newTransformation.block<3,3>(0,0) = Rinv.transpose(); newTransformation.block<3,1>(0,3) = -newTransformation.block<3,3>(0,0) * tinv; transformations.push_back(newTransformation); } return transformations; } } } opengv::transformations_t opengv::absolute_pose::upnp( const AbsoluteAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return upnp(adapter,idx); } opengv::transformations_t opengv::absolute_pose::upnp( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return upnp(adapter,idx); } namespace opengv { namespace absolute_pose { struct OptimizeNonlinearFunctor1 : OptimizationFunctor { const AbsoluteAdapterBase & _adapter; const Indices & _indices; OptimizeNonlinearFunctor1( const AbsoluteAdapterBase & adapter, const Indices & indices ) : OptimizationFunctor(6,indices.size()), _adapter(adapter), _indices(indices) {} int operator()(const VectorXd &x, VectorXd &fvec) const { assert( x.size() == 6 ); assert( (unsigned int) fvec.size() == _indices.size()); //compute the current position translation_t translation = x.block<3,1>(0,0); cayley_t cayley = x.block<3,1>(3,0); rotation_t rotation = math::cayley2rot(cayley); //compute inverse transformation transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = rotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*translation; Eigen::Matrix p_hom; p_hom[3] = 1.0; for(size_t i = 0; i < _indices.size(); i++) { //get point in homogeneous form p_hom.block<3,1>(0,0) = _adapter.getPoint(_indices[i]); //compute the reprojection (this is working for both central and //non-central case) point_t bodyReprojection = inverseSolution * p_hom; point_t reprojection = _adapter.getCamRotation(_indices[i]).transpose() * (bodyReprojection - _adapter.getCamOffset(_indices[i])); reprojection = reprojection / reprojection.norm(); //compute the score double factor = 1.0; fvec[i] = factor * (1.0 - (reprojection.transpose() * _adapter.getBearingVector(_indices[i]))); } return 0; } }; transformation_t optimize_nonlinear( const AbsoluteAdapterBase & adapter, const Indices & indices ) { const int n=6; VectorXd x(n); x.block<3,1>(0,0) = adapter.gett(); x.block<3,1>(3,0) = math::rot2cayley(adapter.getR()); OptimizeNonlinearFunctor1 functor( adapter, indices ); NumericalDiff numDiff(functor); LevenbergMarquardt< NumericalDiff > lm(numDiff); lm.resetParameters(); lm.parameters.ftol = 1.E1*NumTraits::epsilon(); lm.parameters.xtol = 1.E1*NumTraits::epsilon(); lm.parameters.maxfev = 1000; lm.minimize(x); transformation_t transformation; transformation.col(3) = x.block<3,1>(0,0); transformation.block<3,3>(0,0) = math::cayley2rot(x.block<3,1>(3,0)); return transformation; } } } opengv::transformation_t opengv::absolute_pose::optimize_nonlinear( const AbsoluteAdapterBase & adapter ) { Indices idx(adapter.getNumberCorrespondences()); return optimize_nonlinear(adapter,idx); } opengv::transformation_t opengv::absolute_pose::optimize_nonlinear( const AbsoluteAdapterBase & adapter, const std::vector & indices ) { Indices idx(indices); return optimize_nonlinear(adapter,idx); } opengv/src/absolute_pose/MANoncentralAbsolute.cpp0000664016516101651610000001007313344612246021167 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::absolute_pose::MANoncentralAbsolute::MANoncentralAbsolute( const double * points, const double * bearingVectors, int numberPoints, int numberBearingVectors ) : _points(points), _bearingVectors(bearingVectors), _numberPoints(numberPoints), _numberBearingVectors(numberBearingVectors) {} opengv::absolute_pose::MANoncentralAbsolute::~MANoncentralAbsolute() {} opengv::bearingVector_t opengv::absolute_pose::MANoncentralAbsolute:: getBearingVector( size_t index ) const { assert(index < _numberBearingVectors); bearingVector_t bearingVector; bearingVector[0] = _bearingVectors[index * 6]; bearingVector[1] = _bearingVectors[index * 6 + 1]; bearingVector[2] = _bearingVectors[index * 6 + 2]; return bearingVector; } double opengv::absolute_pose::MANoncentralAbsolute:: getWeight( size_t index ) const { return 1.0; } opengv::point_t opengv::absolute_pose::MANoncentralAbsolute:: getPoint( size_t index ) const { point_t point; assert(index < _numberPoints); point[0] = _points[index * 3]; point[1] = _points[index * 3 + 1]; point[2] = _points[index * 3 + 2]; return point; } opengv::translation_t opengv::absolute_pose::MANoncentralAbsolute::getCamOffset( size_t index ) const { assert(index < _numberBearingVectors); translation_t camOffset; camOffset[0] = _bearingVectors[index * 6 + 3]; camOffset[1] = _bearingVectors[index * 6 + 4]; camOffset[2] = _bearingVectors[index * 6 + 5]; return camOffset; } opengv::rotation_t opengv::absolute_pose::MANoncentralAbsolute::getCamRotation( size_t index ) const { return Eigen::Matrix3d::Identity(); } size_t opengv::absolute_pose::MANoncentralAbsolute:: getNumberCorrespondences() const { return _numberBearingVectors; } opengv/src/absolute_pose/CentralAbsoluteAdapter.cpp0000664016516101651610000001041613344612246021540 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::absolute_pose::CentralAbsoluteAdapter::CentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const points_t & points ) : AbsoluteAdapterBase(), _bearingVectors(bearingVectors), _points(points) {} opengv::absolute_pose::CentralAbsoluteAdapter::CentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const points_t & points, const rotation_t & R ) : AbsoluteAdapterBase(R), _bearingVectors(bearingVectors), _points(points) {} opengv::absolute_pose::CentralAbsoluteAdapter::CentralAbsoluteAdapter( const bearingVectors_t & bearingVectors, const points_t & points, const translation_t & t, const rotation_t & R ) : AbsoluteAdapterBase(t,R), _bearingVectors(bearingVectors), _points(points) {} opengv::absolute_pose::CentralAbsoluteAdapter::~CentralAbsoluteAdapter() {} opengv::bearingVector_t opengv::absolute_pose::CentralAbsoluteAdapter::getBearingVector( size_t index ) const { assert(index < _bearingVectors.size()); return _bearingVectors[index]; } double opengv::absolute_pose::CentralAbsoluteAdapter:: getWeight( size_t index ) const { return 1.0; } opengv::point_t opengv::absolute_pose::CentralAbsoluteAdapter::getPoint( size_t index ) const { assert(index < _bearingVectors.size()); return _points[index]; } opengv::translation_t opengv::absolute_pose::CentralAbsoluteAdapter::getCamOffset( size_t index ) const { //we could insert a check here that camIndex is 0, because this adapter is //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::absolute_pose::CentralAbsoluteAdapter::getCamRotation( size_t index ) const { //we could insert a check here that camIndex is 0, because this adapter is //for a single camera only return Eigen::Matrix3d::Identity(); } size_t opengv::absolute_pose::CentralAbsoluteAdapter:: getNumberCorrespondences() const { return _bearingVectors.size(); } opengv/src/absolute_pose/MACentralAbsolute.cpp0000664016516101651610000001004613344612246020454 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::absolute_pose::MACentralAbsolute::MACentralAbsolute( const double * points, const double * bearingVectors, int numberPoints, int numberBearingVectors ) : _points(points), _bearingVectors(bearingVectors), _numberPoints(numberPoints), _numberBearingVectors(numberBearingVectors) {} opengv::absolute_pose::MACentralAbsolute::~MACentralAbsolute() {} opengv::bearingVector_t opengv::absolute_pose::MACentralAbsolute:: getBearingVector( size_t index ) const { assert(index < _numberBearingVectors); bearingVector_t bearingVector; bearingVector[0] = _bearingVectors[index * 3]; bearingVector[1] = _bearingVectors[index * 3 + 1]; bearingVector[2] = _bearingVectors[index * 3 + 2]; return bearingVector; } double opengv::absolute_pose::MACentralAbsolute:: getWeight( size_t index ) const { return 1.0; } opengv::point_t opengv::absolute_pose::MACentralAbsolute:: getPoint( size_t index ) const { point_t point; assert(index < _numberPoints); point[0] = _points[index * 3]; point[1] = _points[index * 3 + 1]; point[2] = _points[index * 3 + 2]; return point; } opengv::translation_t opengv::absolute_pose::MACentralAbsolute::getCamOffset( size_t index ) const { //we could insert a check here that camIndex is 0, because this adapter is //for a single camera only return Eigen::Vector3d::Zero(); } opengv::rotation_t opengv::absolute_pose::MACentralAbsolute::getCamRotation( size_t index ) const { //we could insert a check here that camIndex is 0, because this adapter is //for a single camera only return Eigen::Matrix3d::Identity(); } size_t opengv::absolute_pose::MACentralAbsolute:: getNumberCorrespondences() const { return _numberBearingVectors; } opengv/src/absolute_pose/NoncentralAbsoluteMultiAdapter.cpp0000664016516101651610000001407013344612246023266 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include opengv::absolute_pose::NoncentralAbsoluteMultiAdapter::NoncentralAbsoluteMultiAdapter( std::vector > bearingVectors, std::vector > points, const translations_t & camOffsets, const rotations_t & camRotations ) : _bearingVectors(bearingVectors), _points(points), _camOffsets(camOffsets), _camRotations(camRotations) { // The following variables are needed for the serialization and // de-serialization of indices size_t singleIndexOffset = 0; for( size_t frameIndex = 0; frameIndex < bearingVectors.size(); frameIndex++ ) { singleIndexOffsets.push_back(singleIndexOffset); for( size_t correspondenceIndex = 0; correspondenceIndex < bearingVectors[frameIndex]->size(); correspondenceIndex++ ) { multiFrameIndices.push_back(frameIndex); multiKeypointIndices.push_back(correspondenceIndex); } singleIndexOffset += bearingVectors[frameIndex]->size(); } } opengv::absolute_pose::NoncentralAbsoluteMultiAdapter::~NoncentralAbsoluteMultiAdapter() {} opengv::point_t opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getPoint( size_t frameIndex, size_t correspondenceIndex ) const { assert(frameIndex < _points.size()); assert(correspondenceIndex < _points[frameIndex]->size()); return (*_points[frameIndex])[correspondenceIndex]; } opengv::bearingVector_t opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getBearingVector( size_t frameIndex, size_t correspondenceIndex ) const { assert(frameIndex < _bearingVectors.size()); assert(correspondenceIndex < _bearingVectors[frameIndex]->size()); return (*_bearingVectors[frameIndex])[correspondenceIndex]; } double opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getWeight( size_t frameIndex, size_t correspondenceIndex ) const { return 1.0; } opengv::translation_t opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getMultiCamOffset( size_t frameIndex ) const { assert(frameIndex < _camOffsets.size()); return _camOffsets[frameIndex]; } opengv::rotation_t opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getMultiCamRotation( size_t frameIndex ) const { assert(frameIndex < _camRotations.size()); return _camRotations[frameIndex]; } size_t opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getNumberCorrespondences(size_t frameIndex) const { assert(frameIndex < _bearingVectors.size()); return _bearingVectors[frameIndex]->size(); } size_t opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: getNumberFrames() const { return _camOffsets.size(); } //important conversion between the serialized and the multi interface std::vector opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: convertMultiIndices( const std::vector > & multiIndices ) const { std::vector singleIndices; for(size_t frameIndex = 0; frameIndex < multiIndices.size(); frameIndex++) { for( size_t correspondenceIndex = 0; correspondenceIndex < multiIndices[frameIndex].size(); correspondenceIndex++ ) { singleIndices.push_back(convertMultiIndex( frameIndex, multiIndices[frameIndex][correspondenceIndex] )); } } return singleIndices; } int opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: convertMultiIndex( size_t frameIndex, size_t correspondenceIndex ) const { return singleIndexOffsets[frameIndex]+correspondenceIndex; } int opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: multiFrameIndex( size_t index ) const { return multiFrameIndices[index]; } int opengv::absolute_pose::NoncentralAbsoluteMultiAdapter:: multiCorrespondenceIndex( size_t index ) const { return multiKeypointIndices[index]; } opengv/src/sac_problems/0000775016516101651610000000000013344612246014247 5ustar dimadimaopengv/src/sac_problems/point_cloud/0000775016516101651610000000000013344612246016566 5ustar dimadimaopengv/src/sac_problems/point_cloud/PointCloudSacProblem.cpp0000664016516101651610000000704113344612246023324 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include bool opengv::sac_problems:: point_cloud::PointCloudSacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { outModel = opengv::point_cloud::threept_arun(_adapter,indices); return true; } void opengv::sac_problems:: point_cloud::PointCloudSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < indices.size(); i++ ) { p_hom.block<3,1>(0,0) = _adapter.getPoint2(indices[i]); point_t transformedPoint = model * p_hom; translation_t error = _adapter.getPoint1(indices[i]) - transformedPoint; scores.push_back(error.norm()); } } void opengv::sac_problems:: point_cloud::PointCloudSacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { optimized_model = opengv::point_cloud::threept_arun(_adapter,inliers); } int opengv::sac_problems:: point_cloud::PointCloudSacProblem::getSampleSize() const { int sampleSize = 3; return sampleSize; } opengv/src/sac_problems/relative_pose/0000775016516101651610000000000013344612246017110 5ustar dimadimaopengv/src/sac_problems/relative_pose/TranslationOnlySacProblem.cpp0000664016516101651610000001125613344612246024731 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include bool opengv::sac_problems:: relative_pose::TranslationOnlySacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { outModel.block<3,3>(0,0) = _adapter.getR12(); outModel.col(3) = opengv::relative_pose::twopt(_adapter,true,indices); return true; } void opengv::sac_problems:: relative_pose::TranslationOnlySacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); _adapter.sett12(translation); _adapter.setR12(rotation); model_t inverseSolution; inverseSolution.block<3,3>(0,0) = rotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*translation; Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < indices.size(); i++ ) { p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,indices[i]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(indices[i]); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); scores.push_back(reprojError1 + reprojError2); } } void opengv::sac_problems:: relative_pose::TranslationOnlySacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); _adapter.sett12(translation); _adapter.setR12(rotation); optimized_model = opengv::relative_pose::optimize_nonlinear(_adapter,inliers); } int opengv::sac_problems:: relative_pose::TranslationOnlySacProblem::getSampleSize() const { int sampleSize = 2; return sampleSize; } opengv/src/sac_problems/relative_pose/MultiCentralRelativePoseSacProblem.cpp0000664016516101651610000001704113344612246026515 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include bool opengv::sac_problems:: relative_pose::MultiCentralRelativePoseSacProblem::computeModelCoefficients( const std::vector > &indices, model_t & outModel) const { std::vector > multiTranslations; std::vector > multiRotations; for(size_t pairIndex = 0; pairIndex < _adapter.getNumberPairs(); pairIndex++) { std::vector serializedIndices; for( size_t correspondenceIndex = 0; correspondenceIndex < indices[pairIndex].size(); correspondenceIndex++ ) serializedIndices.push_back(_adapter.convertMultiIndex( pairIndex, indices[pairIndex][correspondenceIndex] )); essential_t essentialMatrix = opengv::relative_pose::eightpt(_adapter,serializedIndices); //Decompose the essential matrix into rotations and translations std::shared_ptr translations(new translations_t()); std::shared_ptr rotations(new rotations_t()); Eigen::Matrix3d W = Eigen::Matrix3d::Zero(); W(0,1) = -1; W(1,0) = 1; W(2,2) = 1; Eigen::JacobiSVD< Eigen::MatrixXd > SVD( essentialMatrix, Eigen::ComputeFullV | Eigen::ComputeFullU ); Eigen::VectorXd singularValues = SVD.singularValues(); // check for bad essential matrix if( singularValues[2] > 0.001 ) {}; // continue; //singularity constraints not applied -> removed because too harsh if( singularValues[1] < 0.75 * singularValues[0] ) {}; // continue; //bad essential matrix -> removed because too harsh // maintain scale double scale = singularValues[0]; // get possible rotation and translation vectors rotation_t Ra = SVD.matrixU() * W * SVD.matrixV().transpose(); rotation_t Rb = SVD.matrixU() * W.transpose() * SVD.matrixV().transpose(); translation_t t = scale*SVD.matrixU().col(2); // change sign if det = -1 if( Ra.determinant() < 0 ) Ra = -Ra; if( Rb.determinant() < 0 ) Rb = -Rb; //Store the decomposition, and already convert to our convention translations->push_back(t); translations->push_back(-t); //this is not needed actually! rotations->push_back(Ra); rotations->push_back(Rb); multiTranslations.push_back(translations); multiRotations.push_back(rotations); } for(size_t pairIndex = 0; pairIndex < _adapter.getNumberPairs(); pairIndex++) { //For each pair, find the right rotation and translation by our critera // // //fill outModel with that (it is a vector of transformations. A //transformation is 3x4 with R from frame 2 to 1, and position of 2 in 1) } return true; } void opengv::sac_problems:: relative_pose::MultiCentralRelativePoseSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector > & indices, std::vector > & scores) const { Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t pairIndex = 0; pairIndex < indices.size(); pairIndex++ ) { translation_t translation = model[pairIndex].col(3); rotation_t rotation = model[pairIndex].block<3,3>(0,0); for( size_t correspondenceIndex = 0; correspondenceIndex < indices[pairIndex].size(); correspondenceIndex++ ) { _adapter.sett12(translation); _adapter.setR12(rotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = rotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*translation; p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2( _adapter, _adapter.convertMultiIndex( pairIndex, indices[pairIndex][correspondenceIndex] )); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(pairIndex,correspondenceIndex); bearingVector_t f2 = _adapter.getBearingVector2(pairIndex,correspondenceIndex); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); scores[pairIndex].push_back(reprojError1 + reprojError2); } } } void opengv::sac_problems:: relative_pose::MultiCentralRelativePoseSacProblem::optimizeModelCoefficients( const std::vector > & inliers, const model_t & model, model_t & optimized_model) { optimized_model = model; //todo: include non-linear optimization of model } std::vector opengv::sac_problems:: relative_pose::MultiCentralRelativePoseSacProblem::getSampleSizes() const { std::vector sampleSizes; for(size_t pairIndex = 0; pairIndex < _adapter.getNumberPairs(); pairIndex++) sampleSizes.push_back(_sampleSize); return sampleSizes; } opengv/src/sac_problems/relative_pose/EigensolverSacProblem.cpp0000664016516101651610000001503313344612246024050 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include bool opengv::sac_problems:: relative_pose::EigensolverSacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { double maxVariation = 0.1; //****** 0.01 ******// //randomize the starting point a bit rotation_t rotation = _adapter.getR12(); cayley_t cayley = math::rot2cayley(rotation); for( size_t i = 0; i < 3; i++ ) cayley[i] = cayley[i] + (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*maxVariation; outModel.rotation = math::cayley2rot(cayley); opengv::relative_pose::eigensolver(_adapter,indices,outModel); return true; } void opengv::sac_problems:: relative_pose::EigensolverSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { /*double referenceNorm = model.translation.norm(); double pureRotation_threshold = 0.0001; double tanAlpha_threshold = tan(0.002); double norm_threshold = 0.001;//0.000625 for(size_t i = 0; i < indices.size(); i++) { bearingVector_t f1 = _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(indices[i]); Eigen::Vector3d n = f1.cross(model.rotation*f2); if( referenceNorm > pureRotation_threshold ) { double np_norm = n.transpose() * model.eigenvectors.col(0); Eigen::Vector3d np = np_norm * model.eigenvectors.col(0); Eigen::Vector3d no = n - np; double maxDistance = norm_threshold + tanAlpha_threshold * no.norm(); scores.push_back(np.norm()/maxDistance); } else scores.push_back(n.norm()/norm_threshold); }*/ translation_t tempTranslation = _adapter.gett12(); rotation_t tempRotation = _adapter.getR12(); translation_t translation = model.translation; rotation_t rotation = model.rotation; _adapter.sett12(translation); _adapter.setR12(rotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = rotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*translation; Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < indices.size(); i++ ) { p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,indices[i]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(indices[i]); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); scores.push_back(reprojError1 + reprojError2); } _adapter.sett12(tempTranslation); _adapter.setR12(tempRotation); } void opengv::sac_problems:: relative_pose::EigensolverSacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { double maxVariation = 0.0; size_t maxIterations = 1; bool firstIteration = true; for(size_t i = 0; i < maxIterations; i++) { model_t temp_optimized_model; //randomize the starting point a bit rotation_t rotation = model.rotation; cayley_t cayley = math::rot2cayley(rotation); for( size_t i = 0; i < 3; i++ ) cayley[i] = cayley[i] + (((double) rand())/ ((double) RAND_MAX)-0.5)*2.0*maxVariation; temp_optimized_model.rotation = math::cayley2rot(cayley); opengv::relative_pose::eigensolver(_adapter,inliers,temp_optimized_model,true); if(firstIteration) { optimized_model = temp_optimized_model; firstIteration = false; } else { if(temp_optimized_model.eigenvalues[0] < optimized_model.eigenvalues[0]) optimized_model = temp_optimized_model; } } } int opengv::sac_problems:: relative_pose::EigensolverSacProblem::getSampleSize() const { return _sampleSize; } opengv/src/sac_problems/relative_pose/CentralRelativePoseSacProblem.cpp0000664016516101651610000002741213344612246025505 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include bool opengv::sac_problems:: relative_pose::CentralRelativePoseSacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { essentials_t essentialMatrices; switch(_algorithm) { case NISTER: { std::vector subIndices1; for(size_t i = 0; i < 5; i++) subIndices1.push_back(indices[i]); essentialMatrices = opengv::relative_pose::fivept_nister(_adapter,subIndices1); break; } case STEWENIUS: { std::vector subIndices2; for(size_t i = 0; i < 5; i++) subIndices2.push_back(indices[i]); complexEssentials_t complexEssentialMatrices = opengv::relative_pose::fivept_stewenius(_adapter,subIndices2); // convert from complexEssential to essential for(size_t i = 0; i < complexEssentialMatrices.size(); i++) { essential_t essentialMatrix; for(size_t r = 0; r < 3; r++) { for(size_t c = 0; c < 3; c++) essentialMatrix(r,c) = complexEssentialMatrices.at(i)(r,c).real(); } essentialMatrices.push_back(essentialMatrix); } break; } case SEVENPT: { std::vector subIndices3; for(size_t i = 0; i < 7; i++) subIndices3.push_back(indices[i]); essentialMatrices = opengv::relative_pose::sevenpt(_adapter,subIndices3); break; } case EIGHTPT: { std::vector subIndices4; for(size_t i = 0; i < 8; i++) subIndices4.push_back(indices[i]); essential_t essentialMatrix = opengv::relative_pose::eightpt(_adapter,subIndices4); essentialMatrices.push_back(essentialMatrix); break; } } //now decompose each essential matrix into transformations and find the //right one Eigen::Matrix3d W = Eigen::Matrix3d::Zero(); W(0,1) = -1; W(1,0) = 1; W(2,2) = 1; double bestQuality = 1000000.0; int bestQualityIndex = -1; int bestQualitySubindex = -1; for(size_t i = 0; i < essentialMatrices.size(); i++) { // decompose Eigen::MatrixXd tempEssential = essentialMatrices[i]; Eigen::JacobiSVD< Eigen::MatrixXd > SVD( tempEssential, Eigen::ComputeFullV | Eigen::ComputeFullU ); Eigen::VectorXd singularValues = SVD.singularValues(); // check for bad essential matrix if( singularValues[2] > 0.001 ) {}; // continue; //singularity constraints not applied -> removed because too harsh if( singularValues[1] < 0.75 * singularValues[0] ) {}; // continue; //bad essential matrix -> removed because too harsh // maintain scale double scale = singularValues[0]; // get possible rotation and translation vectors rotation_t Ra = SVD.matrixU() * W * SVD.matrixV().transpose(); rotation_t Rb = SVD.matrixU() * W.transpose() * SVD.matrixV().transpose(); translation_t ta = scale*SVD.matrixU().col(2); translation_t tb = -ta; // change sign if det = -1 if( Ra.determinant() < 0 ) Ra = -Ra; if( Rb.determinant() < 0 ) Rb = -Rb; //derive transformations transformation_t transformation; transformations_t transformations; transformation.col(3) = ta; transformation.block<3,3>(0,0) = Ra; transformations.push_back(transformation); transformation.col(3) = ta; transformation.block<3,3>(0,0) = Rb; transformations.push_back(transformation); transformation.col(3) = tb; transformation.block<3,3>(0,0) = Ra; transformations.push_back(transformation); transformation.col(3) = tb; transformation.block<3,3>(0,0) = Rb; transformations.push_back(transformation); // derive inverse transformations transformations_t inverseTransformations; for(size_t j = 0; j < 4; j++) { transformation_t inverseTransformation; inverseTransformation.block<3,3>(0,0) = transformations[j].block<3,3>(0,0).transpose(); inverseTransformation.col(3) = -inverseTransformation.block<3,3>(0,0)*transformations[j].col(3); inverseTransformations.push_back(inverseTransformation); } // collect qualities for each of the four solutions solution Eigen::Matrix p_hom; p_hom[3] = 1.0; for(size_t j = 0; j<4; j++) { // prepare variables for triangulation and reprojection _adapter.sett12(transformations[j].col(3)); _adapter.setR12(transformations[j].block<3,3>(0,0)); // go through all features and compute quality of reprojection double quality = 0.0; for( int k = 0; k < getSampleSize(); k++ ) { p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,indices[k]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseTransformations[j] * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(indices[k]); bearingVector_t f2 = _adapter.getBearingVector2(indices[k]); // bearing-vector based outlier criterium (select threshold accordingly): // 1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); quality += reprojError1 + reprojError2; } // is quality better? (lower) if( quality < bestQuality ) { bestQuality = quality; bestQualityIndex = i; bestQualitySubindex = j; } } } if( bestQualityIndex == -1 ) return false; // no solution found else { // rederive the best solution // decompose Eigen::MatrixXd tempEssential = essentialMatrices[bestQualityIndex]; Eigen::JacobiSVD< Eigen::MatrixXd > SVD( tempEssential, Eigen::ComputeFullV | Eigen::ComputeFullU ); const Eigen::VectorXd singularValues = SVD.singularValues(); // maintain scale const double scale = singularValues[0]; // get possible rotation and translation vectors translation_t translation; rotation_t rotation; switch(bestQualitySubindex) { case 0: translation = scale*SVD.matrixU().col(2); rotation = SVD.matrixU() * W * SVD.matrixV().transpose(); break; case 1: translation = scale*SVD.matrixU().col(2); rotation = SVD.matrixU() * W.transpose() * SVD.matrixV().transpose(); break; case 2: translation = -scale*SVD.matrixU().col(2); rotation = SVD.matrixU() * W * SVD.matrixV().transpose(); break; case 3: translation = -scale*SVD.matrixU().col(2); rotation = SVD.matrixU() * W.transpose() * SVD.matrixV().transpose(); break; default: return false; } // change sign if det = -1 if( rotation.determinant() < 0 ) rotation = -rotation; // output final selection outModel.block<3,3>(0,0) = rotation; outModel.col(3) = translation; } return true; } void opengv::sac_problems:: relative_pose::CentralRelativePoseSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); _adapter.sett12(translation); _adapter.setR12(rotation); model_t inverseSolution; inverseSolution.block<3,3>(0,0) = rotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*translation; Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < indices.size(); i++ ) { p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,indices[i]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(indices[i]); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); scores.push_back(reprojError1 + reprojError2); } } void opengv::sac_problems:: relative_pose::CentralRelativePoseSacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); _adapter.sett12(translation); _adapter.setR12(rotation); optimized_model = opengv::relative_pose::optimize_nonlinear(_adapter,inliers); } int opengv::sac_problems:: relative_pose::CentralRelativePoseSacProblem::getSampleSize() const { int sampleSize = 0; switch(_algorithm) { case NISTER: //5 for minimal solver and additional 3 for decomposition and disambiguation sampleSize = 5 + 3; break; case STEWENIUS: //5 for minimal solver and additional 3 for decomposition and disambiguation sampleSize = 5 + 3; break; case SEVENPT: //7 for minimal solver and additional 2 for decomposition and disambiguation sampleSize = 7 + 2; break; case EIGHTPT: //8 for minimal solver and additional 1 for decomposition sampleSize = 8 + 1; break; } return sampleSize; } opengv/src/sac_problems/relative_pose/MultiNoncentralRelativePoseSacProblem.cpp0000664016516101651610000003526013344612246027233 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include bool opengv::sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem:: computeModelCoefficients( const std::vector > &indices, model_t & outModel ) const { bool returnValue = true; if(!_asCentral) { switch(_algorithm) { case SEVENTEENPT: { outModel = opengv::relative_pose::seventeenpt( _adapter,_adapter.convertMultiIndices(indices)); break; } case GE: { geOutput_t output2; opengv::relative_pose::ge( _adapter, _adapter.convertMultiIndices(indices), output2 ); outModel.block<3,3>(0,0) = output2.rotation; outModel.col(3) = output2.translation.block<3,1>(0,0); break; } case SIXPT: { //ok, this block is a bit fancy now, don't ask std::vector sindices; //set it to a random cam index where to start size_t binIndex = floor(((double) _adapter.getNumberPairs()) * ((double) rand()) / ((double) RAND_MAX)); std::vector tempIndices; for( int i = 0; i < (int) indices.size(); i++ ) tempIndices.push_back(0); bool isDone = true; for( int i = 0; i < (int) tempIndices.size(); i++ ) { if (tempIndices[i] < (int) indices[i].size()) { isDone = false; break; } } while( !isDone ) { while( tempIndices[binIndex] >= (int) indices[binIndex].size() ) { binIndex++; if( binIndex >= indices.size() ) binIndex = 0; } sindices.push_back( _adapter.convertMultiIndex( binIndex, indices[binIndex][tempIndices[binIndex]] ) ); (tempIndices[binIndex])++; binIndex++; if( binIndex >= indices.size() ) binIndex = 0; isDone = true; for( int i = 0; i < (int) tempIndices.size(); i++ ) { if (tempIndices[i] < (int) indices[i].size()) { isDone = false; break; } } } std::vector indices6; for( int i = 0; i < 6; i++ ) indices6.push_back(sindices[i]); rotations_t rotations = opengv::relative_pose::sixpt(_adapter,indices6); //now find a translation for each rotation! //as a matter of fact, this should be similar to the end of ge ... transformations_t transformations; for( size_t r = 0; r < rotations.size(); r++ ) { Eigen::Matrix4d G = Eigen::Matrix4d::Zero(); for( int i = 0; i < 6; i++ ) { //extract the features bearingVector_t f1 = _adapter.getCamRotation1(sindices[i]) * _adapter.getBearingVector1(sindices[i]); bearingVector_t f2 = _adapter.getCamRotation2(sindices[i]) * _adapter.getBearingVector2(sindices[i]); //extract the skew symmetric of the camera offsets Eigen::Vector3d t1 = _adapter.getCamOffset1(sindices[i]); Eigen::Matrix3d t1_skew = Eigen::Matrix3d::Zero(); t1_skew(0,1) = -t1[2]; t1_skew(0,2) = t1[1]; t1_skew(1,2) = -t1[0]; t1_skew(1,0) = t1[2]; t1_skew(2,0) = -t1[1]; t1_skew(2,1) = t1[0]; Eigen::Vector3d t2 = _adapter.getCamOffset2(sindices[i]); Eigen::Matrix3d t2_skew = Eigen::Matrix3d::Zero(); t2_skew(0,1) = -t2[2]; t2_skew(0,2) = t2[1]; t2_skew(1,2) = -t2[0]; t2_skew(1,0) = t2[2]; t2_skew(2,0) = -t2[1]; t2_skew(2,1) = t2[0]; //Now compute the "generalized normal vector" Eigen::Vector4d g; g.block<3,1>(0,0) = f1.cross(rotations[r]*f2); g[3] = f1.transpose() * (t1_skew*rotations[r]-rotations[r]*t2_skew) * f2; //Now put that onto G Eigen::Matrix4d newElement = g * g.transpose(); G = G + newElement; } //decompose G to find the rotation Eigen::EigenSolver< Eigen::Matrix4d > Eig(G,true); Eigen::Matrix,4,4> V = Eig.eigenvectors(); double factor = V(3,0).real(); transformation_t transformation; transformation.block<3,3>(0,0) = rotations[r]; for( int k = 0; k < 3; k++ ) transformation(k,3) = (1.0/factor) * V(k,0).real(); transformations.push_back(transformation); } //and finally do the disambiguation (using three more features) //collect qualities for each of the solutions Eigen::Matrix p_hom; p_hom[3] = 1.0; double bestQuality = 1000000.0; int bestQualityIndex = -1; for(size_t i = 0; i < transformations.size(); i++) { // go through all features and compute quality of reprojection double quality = 0.0; for( int k = 6; k < (int) sindices.size(); k++ ) { // prepare variables for triangulation and reprojection translation_t cam1Offset = _adapter.getCamOffset1(sindices[k]); rotation_t cam1Rotation = _adapter.getCamRotation1(sindices[k]); translation_t cam2Offset = _adapter.getCamOffset2(sindices[k]); rotation_t cam2Rotation = _adapter.getCamRotation2(sindices[k]); translation_t directTranslation = cam1Rotation.transpose() * ( (transformations[i].col(3) - cam1Offset) + transformations[i].block<3,3>(0,0) * cam2Offset ); rotation_t directRotation = cam1Rotation.transpose() * transformations[i].block<3,3>(0,0) * cam2Rotation; _adapter.sett12(directTranslation); _adapter.setR12(directRotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = directRotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*directTranslation; p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,sindices[k]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(sindices[k]); bearingVector_t f2 = _adapter.getBearingVector2(sindices[k]); // bearing-vector based outlier criterium (select threshold // accordingly): 1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); quality += reprojError1 + reprojError2; } // is quality better? (lower) if( quality < bestQuality ) { bestQuality = quality; bestQualityIndex = i; } } if( bestQualityIndex == -1 ) returnValue = false; // no solution found else outModel = transformations[bestQualityIndex]; break; } } } else { typedef opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem::algorithm_t algorithm_t; algorithm_t algorithm = opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem::STEWENIUS; opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem centralProblem(_adapter, algorithm); returnValue = centralProblem.computeModelCoefficients( _adapter.convertMultiIndices(indices),outModel); //The transformation has been computed from cam to cam now, so transform //that into the body frame translation_t t_c1c2 = outModel.col(3); rotation_t R_c1c2 = outModel.block<3,3>(0,0); translation_t t_bc = _adapter.getCamOffset(0); rotation_t R_bc = _adapter.getCamRotation(0); outModel.block<3,3>(0,0) = R_bc * R_c1c2 * R_bc.transpose(); outModel.col(3) = t_bc + R_bc * t_c1c2 - outModel.block<3,3>(0,0) * t_bc; } return returnValue; } void opengv::sac_problems::relative_pose:: MultiNoncentralRelativePoseSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector > & indices, std::vector > & scores) const { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t camIndex = 0; camIndex < indices.size(); camIndex++ ) { translation_t cam1Offset = _adapter.getCamOffset(camIndex); rotation_t cam1Rotation = _adapter.getCamRotation(camIndex); translation_t cam2Offset = _adapter.getCamOffset(camIndex); rotation_t cam2Rotation = _adapter.getCamRotation(camIndex); translation_t directTranslation = cam1Rotation.transpose() * ((translation - cam1Offset) + rotation * cam2Offset); rotation_t directRotation = cam1Rotation.transpose() * rotation * cam2Rotation; _adapter.sett12(directTranslation); _adapter.setR12(directRotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = directRotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*directTranslation; for( size_t correspondenceIndex = 0; correspondenceIndex < indices[camIndex].size(); correspondenceIndex++ ) { p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2( _adapter, _adapter.convertMultiIndex( camIndex, indices[camIndex][correspondenceIndex] )); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(camIndex,correspondenceIndex); bearingVector_t f2 = _adapter.getBearingVector2(camIndex,correspondenceIndex); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); scores[camIndex].push_back(reprojError1 + reprojError2); } } } void opengv::sac_problems::relative_pose::MultiNoncentralRelativePoseSacProblem:: optimizeModelCoefficients( const std::vector > & inliers, const model_t & model, model_t & optimized_model) { optimized_model = model; //todo: include non-linear optimization of model translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); _adapter.sett12(translation); _adapter.setR12(rotation); optimized_model = opengv::relative_pose::optimize_nonlinear( _adapter,_adapter.convertMultiIndices(inliers)); } std::vector opengv::sac_problems:: relative_pose::MultiNoncentralRelativePoseSacProblem::getSampleSizes() const { std::vector sampleSizes; for( size_t i = 0; i < _adapter.getNumberPairs(); i++ ) sampleSizes.push_back(0); int sampleSize = 5 + 3; if(!_asCentral) { switch(_algorithm) { case SEVENTEENPT: { sampleSize = 17; break; } case GE: { sampleSize = 8; break; } case SIXPT: { sampleSize = 6 + 3; break; } } } //set it to a random cam index where to start size_t binIndex = floor(((double) _adapter.getNumberPairs()) * ((double) rand()) / ((double) RAND_MAX)); for( int i = 0; i < sampleSize; i++ ) { sampleSizes[binIndex]++; binIndex++; if(binIndex >= sampleSizes.size()) binIndex = 0; } return sampleSizes; } opengv/src/sac_problems/relative_pose/NoncentralRelativePoseSacProblem.cpp0000664016516101651610000003034013344612246026212 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include #include bool opengv::sac_problems:: relative_pose::NoncentralRelativePoseSacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { bool returnValue = true; if(!_asCentral) { switch(_algorithm) { case SEVENTEENPT: { outModel = opengv::relative_pose::seventeenpt(_adapter,indices); break; } case GE: { geOutput_t output2; opengv::relative_pose::ge(_adapter,indices,output2); outModel.block<3,3>(0,0) = output2.rotation; outModel.col(3) = output2.translation.block<3,1>(0,0); break; } case SIXPT: { std::vector indices6; for( int i = 0; i < 6; i++ ) indices6.push_back(indices[i]); rotations_t rotations = opengv::relative_pose::sixpt(_adapter,indices6); //now find a translation for each rotation! //as a matter of fact, this should be similar to the end of ge ... transformations_t transformations; for( size_t r = 0; r < rotations.size(); r++ ) { Eigen::Matrix4d G = Eigen::Matrix4d::Zero(); for( int i = 0; i < 6; i++ ) { //extract the features bearingVector_t f1 = _adapter.getCamRotation1(indices[i]) * _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getCamRotation2(indices[i]) * _adapter.getBearingVector2(indices[i]); //extract the skew symmetric of the camera offsets Eigen::Vector3d t1 = _adapter.getCamOffset1(indices[i]); Eigen::Matrix3d t1_skew = Eigen::Matrix3d::Zero(); t1_skew(0,1) = -t1[2]; t1_skew(0,2) = t1[1]; t1_skew(1,2) = -t1[0]; t1_skew(1,0) = t1[2]; t1_skew(2,0) = -t1[1]; t1_skew(2,1) = t1[0]; Eigen::Vector3d t2 = _adapter.getCamOffset2(indices[i]); Eigen::Matrix3d t2_skew = Eigen::Matrix3d::Zero(); t2_skew(0,1) = -t2[2]; t2_skew(0,2) = t2[1]; t2_skew(1,2) = -t2[0]; t2_skew(1,0) = t2[2]; t2_skew(2,0) = -t2[1]; t2_skew(2,1) = t2[0]; //Now compute the "generalized normal vector" Eigen::Vector4d g; g.block<3,1>(0,0) = f1.cross(rotations[r]*f2); g[3] = f1.transpose() * (t1_skew*rotations[r]-rotations[r]*t2_skew) * f2; //Now put that onto G Eigen::Matrix4d newElement = g * g.transpose(); G = G + newElement; } //decompose G to find the rotation Eigen::EigenSolver< Eigen::Matrix4d > Eig(G,true); Eigen::Matrix,4,4> V = Eig.eigenvectors(); double factor = V(3,0).real(); transformation_t transformation; transformation.block<3,3>(0,0) = rotations[r]; for( int k = 0; k < 3; k++ ) transformation(k,3) = (1.0/factor) * V(k,0).real(); transformations.push_back(transformation); } //and finally do the disambiguation (using three more features) //collect qualities for each of the solutions Eigen::Matrix p_hom; p_hom[3] = 1.0; double bestQuality = 1000000.0; int bestQualityIndex = -1; for(size_t i = 0; i < transformations.size(); i++) { // go through all features and compute quality of reprojection double quality = 0.0; for( int k = 6; k < getSampleSize(); k++ ) { // prepare variables for triangulation and reprojection translation_t cam1Offset = _adapter.getCamOffset1(indices[k]); rotation_t cam1Rotation = _adapter.getCamRotation1(indices[k]); translation_t cam2Offset = _adapter.getCamOffset2(indices[k]); rotation_t cam2Rotation = _adapter.getCamRotation2(indices[k]); translation_t directTranslation = cam1Rotation.transpose() * ((transformations[i].col(3) - cam1Offset) + transformations[i].block<3,3>(0,0) * cam2Offset); rotation_t directRotation = cam1Rotation.transpose() * transformations[i].block<3,3>(0,0) * cam2Rotation; _adapter.sett12(directTranslation); _adapter.setR12(directRotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = directRotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*directTranslation; p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,indices[k]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(indices[k]); bearingVector_t f2 = _adapter.getBearingVector2(indices[k]); // bearing-vector based outlier criterium (select threshold accordingly): // 1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); quality += reprojError1 + reprojError2; } // is quality better? (lower) if( quality < bestQuality ) { bestQuality = quality; bestQualityIndex = i; } } if( bestQualityIndex == -1 ) returnValue = false; // no solution found else outModel = transformations[bestQualityIndex]; break; } } } else { typedef opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem::algorithm_t algorithm_t; algorithm_t algorithm = opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem::STEWENIUS; opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem centralProblem(_adapter, algorithm); returnValue = centralProblem.computeModelCoefficients(indices,outModel); //The transformation has been computed from cam to cam now, so transform that into the body frame translation_t t_c1c2 = outModel.col(3); rotation_t R_c1c2 = outModel.block<3,3>(0,0); translation_t t_bc1 = _adapter.getCamOffset1(indices[0]); rotation_t R_bc1 = _adapter.getCamRotation1(indices[0]); translation_t t_bc2 = _adapter.getCamOffset2(indices[0]); rotation_t R_bc2 = _adapter.getCamRotation2(indices[0]); outModel.block<3,3>(0,0) = R_bc1 * R_c1c2 * R_bc2.transpose(); outModel.col(3) = t_bc1 + R_bc1 * t_c1c2 - outModel.block<3,3>(0,0) * t_bc2; } return returnValue; } void opengv::sac_problems:: relative_pose::NoncentralRelativePoseSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); Eigen::Matrix p_hom; p_hom[3] = 1.0; for( size_t i = 0; i < indices.size(); i++ ) { translation_t cam1Offset = _adapter.getCamOffset1(indices[i]); rotation_t cam1Rotation = _adapter.getCamRotation1(indices[i]); translation_t cam2Offset = _adapter.getCamOffset2(indices[i]); rotation_t cam2Rotation = _adapter.getCamRotation2(indices[i]); translation_t directTranslation = cam1Rotation.transpose() * ((translation - cam1Offset) + rotation * cam2Offset); rotation_t directRotation = cam1Rotation.transpose() * rotation * cam2Rotation; _adapter.sett12(directTranslation); _adapter.setR12(directRotation); transformation_t inverseSolution; inverseSolution.block<3,3>(0,0) = directRotation.transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*directTranslation; p_hom.block<3,1>(0,0) = opengv::triangulation::triangulate2(_adapter,indices[i]); bearingVector_t reprojection1 = p_hom.block<3,1>(0,0); bearingVector_t reprojection2 = inverseSolution * p_hom; reprojection1 = reprojection1 / reprojection1.norm(); reprojection2 = reprojection2 / reprojection2.norm(); bearingVector_t f1 = _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(indices[i]); //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double reprojError1 = 1.0 - (f1.transpose() * reprojection1); double reprojError2 = 1.0 - (f2.transpose() * reprojection2); scores.push_back(reprojError1 + reprojError2); } } void opengv::sac_problems:: relative_pose::NoncentralRelativePoseSacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { translation_t translation = model.col(3); rotation_t rotation = model.block<3,3>(0,0); _adapter.sett12(translation); _adapter.setR12(rotation); optimized_model = opengv::relative_pose::optimize_nonlinear(_adapter,inliers); } int opengv::sac_problems:: relative_pose::NoncentralRelativePoseSacProblem::getSampleSize() const { int sampleSize = 5 + 3; if(!_asCentral) { switch(_algorithm) { case SEVENTEENPT: { sampleSize = 17; break; } case GE: { sampleSize = 8; break; } case SIXPT: { sampleSize = 6 + 3; break; } } } return sampleSize; } opengv/src/sac_problems/relative_pose/RotationOnlySacProblem.cpp0000664016516101651610000000750513344612246024234 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include #include #include #include bool opengv::sac_problems:: relative_pose::RotationOnlySacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { outModel = opengv::relative_pose::twopt_rotationOnly(_adapter,indices); return true; } void opengv::sac_problems:: relative_pose::RotationOnlySacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { for( size_t i = 0; i < indices.size(); i++ ) { bearingVector_t f1 = _adapter.getBearingVector1(indices[i]); bearingVector_t f2 = _adapter.getBearingVector2(indices[i]); //unrotate bearing-vector f2 bearingVector_t f2_unrotated = model * f2; //bearing-vector based outlier criterium (select threshold accordingly): //1-(f1'*f2) = 1-cos(alpha) \in [0:2] double error = 1.0 - (f1.transpose() * f2_unrotated); scores.push_back(error); } } void opengv::sac_problems:: relative_pose::RotationOnlySacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { optimized_model = opengv::relative_pose::rotationOnly(_adapter,inliers); } int opengv::sac_problems:: relative_pose::RotationOnlySacProblem::getSampleSize() const { int sampleSize = 2; return sampleSize; } opengv/src/sac_problems/absolute_pose/0000775016516101651610000000000013344612246017113 5ustar dimadimaopengv/src/sac_problems/absolute_pose/MultiNoncentralAbsolutePoseSacProblem.cpp0000664016516101651610000001600613344612246027236 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include bool opengv::sac_problems:: absolute_pose::MultiNoncentralAbsolutePoseSacProblem::computeModelCoefficients( const std::vector< std::vector > & indices, model_t & outModel) const { transformations_t solutions; std::vector stratifiedIndices = _adapter.convertMultiIndices(indices); if(!_asCentral) { solutions = opengv::absolute_pose::gp3p( _adapter,stratifiedIndices); } else { solutions = opengv::absolute_pose::p3p_kneip( _adapter,stratifiedIndices); //transform solution into body frame (case of single shifted cam) translation_t t_bc = _adapter.getCamOffset(0); rotation_t R_bc = _adapter.getCamRotation(0); for(size_t i = 0; i < solutions.size(); i++) { translation_t translation = solutions[i].col(3); rotation_t rotation = solutions[i].block<3,3>(0,0); solutions[i].col(3) = translation - rotation * R_bc.transpose() * t_bc; solutions[i].block<3,3>(0,0) = rotation * R_bc.transpose(); } } if( solutions.size() == 1 ) { outModel = solutions[0]; return true; } //now compute reprojection error of fourth point, in order to find the right one double minScore = 1000000.0; int minIndex = -1; for(size_t i = 0; i < solutions.size(); i++) { //compute inverse transformation model_t inverseSolution; inverseSolution.block<3,3>(0,0) = solutions[i].block<3,3>(0,0).transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*solutions[i].col(3); //get the fourth point in homogeneous form Eigen::Matrix p_hom; p_hom.block<3,1>(0,0) = _adapter.getPoint(stratifiedIndices[3]); p_hom[3] = 1.0; //compute the reprojection (this is working for both central and //non-central case) point_t bodyReprojection = inverseSolution * p_hom; point_t reprojection = _adapter.getCamRotation(stratifiedIndices[3]).transpose() * (bodyReprojection - _adapter.getCamOffset(stratifiedIndices[3])); reprojection = reprojection / reprojection.norm(); //compute the score double score = 1.0 - (reprojection.transpose() * _adapter.getBearingVector(stratifiedIndices[3])); //check for best solution if( score < minScore ) { minScore = score; minIndex = i; } } if(minIndex == -1) return false; outModel = solutions[minIndex]; return true; } void opengv::sac_problems:: absolute_pose::MultiNoncentralAbsolutePoseSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector > & indices, std::vector > & scores) const { //compute the reprojection error of all points //compute inverse transformation model_t inverseSolution; inverseSolution.block<3,3>(0,0) = model.block<3,3>(0,0).transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*model.col(3); Eigen::Matrix p_hom; p_hom[3] = 1.0; for(size_t f = 0; f < indices.size(); f++ ) { for(size_t i = 0; i < indices[f].size(); i++) { //get point in homogeneous form p_hom.block<3,1>(0,0) = _adapter.getPoint(f,indices[f][i]); //compute the reprojection (this is working for both central and //non-central case) point_t bodyReprojection = inverseSolution * p_hom; point_t reprojection = _adapter.getMultiCamRotation(f).transpose() * (bodyReprojection - _adapter.getMultiCamOffset(f)); reprojection = reprojection / reprojection.norm(); //compute the score scores[f].push_back( 1.0 - (reprojection.transpose() * _adapter.getBearingVector(f,indices[f][i]))); } } } void opengv::sac_problems:: absolute_pose::MultiNoncentralAbsolutePoseSacProblem::optimizeModelCoefficients( const std::vector< std::vector > & inliers, const model_t & model, model_t & optimized_model) { _adapter.sett(model.col(3)); _adapter.setR(model.block<3,3>(0,0)); optimized_model = opengv::absolute_pose::optimize_nonlinear(_adapter,_adapter.convertMultiIndices(inliers)); } std::vector opengv::sac_problems:: absolute_pose::MultiNoncentralAbsolutePoseSacProblem::getSampleSizes() const { std::vector sampleSizes; for( size_t i = 0; i < _adapter.getNumberFrames(); i++ ) sampleSizes.push_back(0); int sampleSize = 4; //set it to a random cam index where to start size_t binIndex = floor(((double) _adapter.getNumberFrames()) * ((double) rand()) / ((double) RAND_MAX)); for( int i = 0; i < sampleSize; i++ ) { sampleSizes[binIndex]++; binIndex++; if(binIndex >= sampleSizes.size()) binIndex = 0; } return sampleSizes; } opengv/src/sac_problems/absolute_pose/AbsolutePoseSacProblem.cpp0000664016516101651610000001767213344612246024211 0ustar dimadima/****************************************************************************** * Author: Laurent Kneip * * Contact: kneip.laurent@gmail.com * * License: Copyright (c) 2013 Laurent Kneip, ANU. All rights reserved. * * * * Redistribution and use in source and binary forms, with or without * * modification, are permitted provided that the following conditions * * are met: * * * Redistributions of source code must retain the above copyright * * notice, this list of conditions and the following disclaimer. * * * Redistributions in binary form must reproduce the above copyright * * notice, this list of conditions and the following disclaimer in the * * documentation and/or other materials provided with the distribution. * * * Neither the name of ANU nor the names of its contributors may be * * used to endorse or promote products derived from this software without * * specific prior written permission. * * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"* * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE * * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY * * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * * SUCH DAMAGE. * ******************************************************************************/ #include #include bool opengv::sac_problems:: absolute_pose::AbsolutePoseSacProblem::computeModelCoefficients( const std::vector &indices, model_t & outModel) const { transformations_t solutions; switch(_algorithm) { case TWOPT: { rotation_t rotation = _adapter.getR(); translation_t translation = opengv::absolute_pose::p2p(_adapter,indices); transformation_t solution; translation_t t_bc = _adapter.getCamOffset(indices[0]); rotation_t R_bc = _adapter.getCamRotation(indices[0]); solution.col(3) = translation - rotation * R_bc.transpose() * t_bc; solution.block<3,3>(0,0) = rotation * R_bc.transpose(); solutions.push_back(solution); break; } case KNEIP: { solutions = opengv::absolute_pose::p3p_kneip(_adapter,indices); //transform solution into body frame (case of single shifted cam) translation_t t_bc = _adapter.getCamOffset(indices[0]); rotation_t R_bc = _adapter.getCamRotation(indices[0]); for(size_t i = 0; i < solutions.size(); i++) { translation_t translation = solutions[i].col(3); rotation_t rotation = solutions[i].block<3,3>(0,0); solutions[i].col(3) = translation - rotation * R_bc.transpose() * t_bc; solutions[i].block<3,3>(0,0) = rotation * R_bc.transpose(); } break; } case GAO: { solutions = opengv::absolute_pose::p3p_gao(_adapter,indices); //transform solution into body frame (case of single shifted cam) translation_t t_bc = _adapter.getCamOffset(indices[0]); rotation_t R_bc = _adapter.getCamRotation(indices[0]); for(size_t i = 0; i < solutions.size(); i++) { translation_t translation = solutions[i].col(3); rotation_t rotation = solutions[i].block<3,3>(0,0); solutions[i].col(3) = translation - rotation * R_bc.transpose() * t_bc; solutions[i].block<3,3>(0,0) = rotation * R_bc.transpose(); } break; } case EPNP: { transformation_t solution = opengv::absolute_pose::epnp(_adapter,indices); //transform solution into body frame (case of single shifted cam) translation_t t_bc = _adapter.getCamOffset(indices[0]); rotation_t R_bc = _adapter.getCamRotation(indices[0]); translation_t translation = solution.col(3); rotation_t rotation = solution.block<3,3>(0,0); solution.col(3) = translation - rotation * R_bc.transpose() * t_bc; solution.block<3,3>(0,0) = rotation * R_bc.transpose(); solutions.push_back(solution); break; } case GP3P: { solutions = opengv::absolute_pose::gp3p(_adapter,indices); break; } } if( solutions.size() == 1 ) { outModel = solutions[0]; return true; } //now compute reprojection error of fourth point, in order to find the right one double minScore = 1000000.0; int minIndex = -1; for(size_t i = 0; i < solutions.size(); i++) { //compute inverse transformation model_t inverseSolution; inverseSolution.block<3,3>(0,0) = solutions[i].block<3,3>(0,0).transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*solutions[i].col(3); //get the fourth point in homogeneous form Eigen::Matrix p_hom; p_hom.block<3,1>(0,0) = _adapter.getPoint(indices[3]); p_hom[3] = 1.0; //compute the reprojection (this is working for both central and //non-central case) point_t bodyReprojection = inverseSolution * p_hom; point_t reprojection = _adapter.getCamRotation(indices[3]).transpose() * (bodyReprojection - _adapter.getCamOffset(indices[3])); reprojection = reprojection / reprojection.norm(); //compute the score double score = 1.0 - (reprojection.transpose() * _adapter.getBearingVector(indices[3])); //check for best solution if( score < minScore ) { minScore = score; minIndex = i; } } if(minIndex == -1) return false; outModel = solutions[minIndex]; return true; } void opengv::sac_problems:: absolute_pose::AbsolutePoseSacProblem::getSelectedDistancesToModel( const model_t & model, const std::vector & indices, std::vector & scores) const { //compute the reprojection error of all points //compute inverse transformation model_t inverseSolution; inverseSolution.block<3,3>(0,0) = model.block<3,3>(0,0).transpose(); inverseSolution.col(3) = -inverseSolution.block<3,3>(0,0)*model.col(3); Eigen::Matrix p_hom; p_hom[3] = 1.0; for(size_t i = 0; i < indices.size(); i++) { //get point in homogeneous form p_hom.block<3,1>(0,0) = _adapter.getPoint(indices[i]); //compute the reprojection (this is working for both central and //non-central case) point_t bodyReprojection = inverseSolution * p_hom; point_t reprojection = _adapter.getCamRotation(indices[i]).transpose() * (bodyReprojection - _adapter.getCamOffset(indices[i])); reprojection = reprojection / reprojection.norm(); //compute the score scores.push_back( 1.0 - (reprojection.transpose() * _adapter.getBearingVector(indices[i]))); } } void opengv::sac_problems:: absolute_pose::AbsolutePoseSacProblem::optimizeModelCoefficients( const std::vector & inliers, const model_t & model, model_t & optimized_model) { _adapter.sett(model.col(3)); _adapter.setR(model.block<3,3>(0,0)); optimized_model = opengv::absolute_pose::optimize_nonlinear(_adapter,inliers); } int opengv::sac_problems:: absolute_pose::AbsolutePoseSacProblem::getSampleSize() const { int sampleSize = 4; if(_algorithm == TWOPT) sampleSize = 2; if(_algorithm == EPNP) sampleSize = 6; return sampleSize; } opengv/manifest.xml0000664016516101651610000000057713344612246013350 0ustar dimadima opengv Laurent Kneip FreeBSD http://ros.org/wiki/opengv